46 namespace joint_trajectory_interface
49 #define ROS_ERROR_RETURN(rtn,...) do {ROS_ERROR(__VA_ARGS__); return(rtn);} while(0)
51 bool JointTrajectoryInterface::init(std::string default_ip,
int default_port)
57 ros::param::param<std::string>(
"robot_ip_address", ip, default_ip);
58 ros::param::param<int>(
"~port", port, default_port);
63 ROS_ERROR(
"No valid robot IP address found. Please set ROS 'robot_ip_address' param");
68 ROS_ERROR(
"No valid robot IP port found. Please set ROS '~port' param");
72 char* ip_addr = strdup(ip.c_str());
73 ROS_INFO(
"Joint Trajectory Interface connecting to IP address: '%s:%d'", ip_addr, port);
74 default_tcp_connection_.init(ip_addr, port);
77 return init(&default_tcp_connection_);
82 std::vector<std::string> joint_names;
83 if (!
getJointNames(
"controller_joint_names",
"robot_description", joint_names))
85 ROS_ERROR(
"Failed to initialize joint_names. Aborting");
89 return init(connection, joint_names);
92 bool JointTrajectoryInterface::init(
SmplMsgConnection* connection,
const std::vector<std::string> &joint_names,
93 const std::map<std::string, double> &velocity_limits)
95 this->connection_ = connection;
96 this->all_joint_names_ = joint_names;
97 this->joint_vel_limits_ = velocity_limits;
102 ROS_WARN(
"Unable to read velocity limits from 'robot_description' param. Velocity validation disabled.");
104 this->srv_stop_motion_ = this->node_.advertiseService(
"stop_motion", &JointTrajectoryInterface::stopMotionCB,
this);
105 this->srv_joint_trajectory_ = this->node_.advertiseService(
"joint_path_command", &JointTrajectoryInterface::jointTrajectoryCB,
this);
106 this->sub_joint_trajectory_ = this->node_.subscribe(
"joint_path_command", 0, &JointTrajectoryInterface::jointTrajectoryCB,
this);
107 this->sub_cur_pos_ = this->node_.subscribe(
"joint_states", 1, &JointTrajectoryInterface::jointStateCB,
this);
112 JointTrajectoryInterface::~JointTrajectoryInterface()
115 this->sub_joint_trajectory_.shutdown();
118 bool JointTrajectoryInterface::jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
119 industrial_msgs::CmdJointTrajectory::Response &res)
121 trajectory_msgs::JointTrajectoryPtr traj_ptr(
new trajectory_msgs::JointTrajectory);
122 *traj_ptr = req.trajectory;
123 this->jointTrajectoryCB(traj_ptr);
126 res.code.val = industrial_msgs::ServiceReturnCode::SUCCESS;
131 void JointTrajectoryInterface::jointTrajectoryCB(
const trajectory_msgs::JointTrajectoryConstPtr &msg)
133 ROS_INFO(
"Receiving joint trajectory message");
136 if (msg->points.empty())
138 ROS_INFO(
"Empty trajectory received, canceling current trajectory");
144 std::vector<JointTrajPtMessage> robot_msgs;
145 if (!trajectory_to_msgs(msg, &robot_msgs))
149 send_to_robot(robot_msgs);
152 bool JointTrajectoryInterface::trajectory_to_msgs(
const trajectory_msgs::JointTrajectoryConstPtr& traj, std::vector<JointTrajPtMessage>* msgs)
157 if (!is_valid(*traj))
160 for (
size_t i=0; i<traj->points.size(); ++i)
163 double vel, duration;
166 if (!select(traj->joint_names, traj->points[i], this->all_joint_names_, &rbt_pt))
170 if (!transform(rbt_pt, &xform_pt))
174 if (!calc_speed(xform_pt, &vel, &duration))
178 msgs->push_back(msg);
184 bool JointTrajectoryInterface::select(
const std::vector<std::string>& ros_joint_names,
const ros_JointTrajPt& ros_pt,
185 const std::vector<std::string>& rbt_joint_names,
ros_JointTrajPt* rbt_pt)
187 ROS_ASSERT(ros_joint_names.size() == ros_pt.positions.size());
191 rbt_pt->positions.clear(); rbt_pt->velocities.clear(); rbt_pt->accelerations.clear();
193 for (
size_t rbt_idx=0; rbt_idx < rbt_joint_names.size(); ++rbt_idx)
195 bool is_empty = rbt_joint_names[rbt_idx].empty();
198 size_t ros_idx = std::find(ros_joint_names.begin(), ros_joint_names.end(), rbt_joint_names[rbt_idx]) - ros_joint_names.begin();
199 bool is_found = ros_idx < ros_joint_names.size();
202 if (!is_empty && !is_found)
204 ROS_ERROR(
"Expected joint (%s) not found in JointTrajectory. Aborting command.", rbt_joint_names[rbt_idx].c_str());
210 if (!ros_pt.positions.empty()) rbt_pt->positions.push_back(default_joint_pos_);
211 if (!ros_pt.velocities.empty()) rbt_pt->velocities.push_back(-1);
212 if (!ros_pt.accelerations.empty()) rbt_pt->accelerations.push_back(-1);
216 if (!ros_pt.positions.empty()) rbt_pt->positions.push_back(ros_pt.positions[ros_idx]);
217 if (!ros_pt.velocities.empty()) rbt_pt->velocities.push_back(ros_pt.velocities[ros_idx]);
218 if (!ros_pt.accelerations.empty()) rbt_pt->accelerations.push_back(ros_pt.accelerations[ros_idx]);
224 bool JointTrajectoryInterface::calc_speed(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_velocity,
double* rbt_duration)
226 return calc_velocity(pt, rbt_velocity) && calc_duration(pt, rbt_duration);
235 bool JointTrajectoryInterface::calc_velocity(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_velocity)
237 std::vector<double> vel_ratios;
239 ROS_ASSERT(all_joint_names_.size() == pt.positions.size());
242 if (pt.velocities.empty())
244 ROS_WARN(
"Joint velocities unspecified. Using default/safe speed.");
245 *rbt_velocity = default_vel_ratio_;
249 for (
size_t i=0; i<all_joint_names_.size(); ++i)
251 const std::string &jnt_name = all_joint_names_[i];
254 if (jnt_name.empty())
255 vel_ratios.push_back(-1);
256 else if (joint_vel_limits_.count(jnt_name) == 0)
257 vel_ratios.push_back(-1);
259 vel_ratios.push_back( fabs(pt.velocities[i] / joint_vel_limits_[jnt_name]) );
263 int max_idx = std::max_element(vel_ratios.begin(), vel_ratios.end()) - vel_ratios.begin();
265 if (vel_ratios[max_idx] > 0)
266 *rbt_velocity = vel_ratios[max_idx];
269 ROS_WARN_ONCE(
"Joint velocity-limits unspecified. Using default velocity-ratio.");
270 *rbt_velocity = default_vel_ratio_;
273 if ( (*rbt_velocity < 0) || (*rbt_velocity > 1) )
275 ROS_WARN(
"computed velocity (%.1f %%) is out-of-range. Clipping to [0-100%%]", *rbt_velocity * 100);
276 *rbt_velocity = std::min(1.0, std::max(0.0, *rbt_velocity));
282 bool JointTrajectoryInterface::calc_duration(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_duration)
284 std::vector<double> durations;
285 double this_time = pt.time_from_start.toSec();
286 static double last_time = 0;
288 if (this_time <= last_time)
289 *rbt_duration = default_duration_;
291 *rbt_duration = this_time - last_time;
293 last_time = this_time;
298 JointTrajPtMessage JointTrajectoryInterface::create_message(
int seq, std::vector<double> joint_pos,
double velocity,
double duration)
303 for (
size_t i=0; i<joint_pos.size(); ++i)
307 pt.
init(seq, pos, velocity, duration);
315 void JointTrajectoryInterface::trajectoryStop()
320 ROS_INFO(
"Joint trajectory handler: entering stopping state");
321 jMsg.
setSequence(SpecialSeqValues::STOP_TRAJECTORY);
324 this->connection_->sendAndReceiveMsg(msg, reply);
327 bool JointTrajectoryInterface::stopMotionCB(industrial_msgs::StopMotion::Request &req,
328 industrial_msgs::StopMotion::Response &res)
333 res.code.val = industrial_msgs::ServiceReturnCode::SUCCESS;
338 bool JointTrajectoryInterface::is_valid(
const trajectory_msgs::JointTrajectory &traj)
340 for (
int i=0; i<traj.points.size(); ++i)
342 const trajectory_msgs::JointTrajectoryPoint &pt = traj.points[i];
345 if (pt.positions.empty())
346 ROS_ERROR_RETURN(
false,
"Validation failed: Missing position data for trajectory pt %d", i);
349 for (
int j=0; j<pt.velocities.size(); ++j)
351 std::map<std::string, double>::iterator max_vel = joint_vel_limits_.find(traj.joint_names[j]);
352 if (max_vel == joint_vel_limits_.end())
continue;
354 if (std::abs(pt.velocities[j]) > max_vel->second)
355 ROS_ERROR_RETURN(
false,
"Validation failed: Max velocity exceeded for trajectory pt %d, joint '%s'", i, traj.joint_names[j].c_str());
359 if ((i > 0) && (pt.time_from_start.toSec() == 0))
360 ROS_ERROR_RETURN(
false,
"Validation failed: Missing valid timestamp data for trajectory pt %d", i);
367 void JointTrajectoryInterface::jointStateCB(
const sensor_msgs::JointStateConstPtr &msg)
369 this->cur_joint_pos_ = *msg;