1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Add speed interface

This commit is contained in:
Thomas Timm Andersen
2015-09-09 13:34:21 +02:00
parent 326c9fbb59
commit 816f1215c8

View File

@@ -17,6 +17,7 @@
#include <mutex>
#include <condition_variable>
#include <thread>
#include <algorithm>
#include "sensor_msgs/JointState.h"
#include "geometry_msgs/WrenchStamped.h"
@@ -24,8 +25,6 @@
#include "actionlib/server/simple_action_server.h"
#include "trajectory_msgs/JointTrajectoryPoint.h"
class RosWrapper {
protected:
ros::NodeHandle nh_;
@@ -161,7 +160,14 @@ private:
traj.points = new_traj;
}
void speedInterface(const trajectory_msgs::JointTrajectory::ConstPtr& msg) {
void speedInterface(const trajectory_msgs::JointTrajectory::Ptr& msg) {
reorder_traj_joints(*msg);
double acc = *std::max_element(msg->points[0].accelerations.begin(),
msg->points[0].accelerations.end());
robot_.setSpeed(msg->points[0].velocities[0],
msg->points[0].velocities[1], msg->points[0].velocities[2],
msg->points[0].velocities[3], msg->points[0].velocities[4],
msg->points[0].velocities[5], acc);
}