00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <algorithm>
00033 #include "fs100/industrial_robot_client/joint_trajectory_interface.h"
00034 #include "simple_message/joint_traj_pt.h"
00035 #include "industrial_utils/param_utils.h"
00036
00037 using namespace industrial_utils::param;
00038 using industrial::simple_message::SimpleMessage;
00039 namespace SpecialSeqValues = industrial::joint_traj_pt::SpecialSeqValues;
00040 typedef industrial::joint_traj_pt::JointTrajPt rbt_JointTrajPt;
00041 typedef trajectory_msgs::JointTrajectoryPoint ros_JointTrajPt;
00042
00043 namespace industrial_robot_client
00044 {
00045 namespace joint_trajectory_interface
00046 {
00047
00048 #define ROS_ERROR_RETURN(rtn,...) do {ROS_ERROR(__VA_ARGS__); return(rtn);} while(0)
00049
00050 bool JointTrajectoryInterface::init(std::string default_ip, int default_port)
00051 {
00052 std::string ip;
00053 int port;
00054
00055
00056 ros::param::param<std::string>("robot_ip_address", ip, default_ip);
00057 ros::param::param<int>("~port", port, default_port);
00058
00059
00060 if (ip.empty())
00061 {
00062 ROS_ERROR("No valid robot IP address found. Please set ROS 'robot_ip_address' param");
00063 return false;
00064 }
00065 if (port <= 0)
00066 {
00067 ROS_ERROR("No valid robot IP port found. Please set ROS '~port' param");
00068 return false;
00069 }
00070
00071 char* ip_addr = strdup(ip.c_str());
00072 ROS_INFO("Joint Trajectory Interface connecting to IP address: '%s:%d'", ip_addr, port);
00073 default_tcp_connection_.init(ip_addr, port);
00074 free(ip_addr);
00075
00076 return init(&default_tcp_connection_);
00077 }
00078
00079 bool JointTrajectoryInterface::init(SmplMsgConnection* connection)
00080 {
00081 std::vector<std::string> joint_names;
00082 if (!getJointNames("controller_joint_names", "robot_description", joint_names))
00083 {
00084 ROS_ERROR("Failed to initialize joint_names. Aborting");
00085 return false;
00086 }
00087
00088 return init(connection, joint_names);
00089 }
00090
00091 bool JointTrajectoryInterface::init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00092 const std::map<std::string, double> &velocity_limits)
00093 {
00094 this->connection_ = connection;
00095 this->all_joint_names_ = joint_names;
00096 this->joint_vel_limits_ = velocity_limits;
00097 connection_->makeConnect();
00098
00099
00100 if (joint_vel_limits_.empty() && !industrial_utils::param::getJointVelocityLimits("robot_description", joint_vel_limits_))
00101 ROS_WARN("Unable to read velocity limits from 'robot_description' param. Velocity validation disabled.");
00102
00103 this->srv_stop_motion_ = this->node_.advertiseService("stop_motion", &JointTrajectoryInterface::stopMotionCB, this);
00104 this->srv_joint_trajectory_ = this->node_.advertiseService("joint_path_command", &JointTrajectoryInterface::jointTrajectoryCB, this);
00105 this->sub_joint_trajectory_ = this->node_.subscribe("joint_path_command", 0, &JointTrajectoryInterface::jointTrajectoryCB, this);
00106 this->sub_cur_pos_ = this->node_.subscribe("joint_states", 1, &JointTrajectoryInterface::jointStateCB, this);
00107
00108 return true;
00109 }
00110
00111 JointTrajectoryInterface::~JointTrajectoryInterface()
00112 {
00113 trajectoryStop();
00114 this->sub_joint_trajectory_.shutdown();
00115 }
00116
00117 bool JointTrajectoryInterface::jointTrajectoryCB(industrial_msgs::CmdJointTrajectory::Request &req,
00118 industrial_msgs::CmdJointTrajectory::Response &res)
00119 {
00120 trajectory_msgs::JointTrajectoryPtr traj_ptr(new trajectory_msgs::JointTrajectory);
00121 *traj_ptr = req.trajectory;
00122 this->jointTrajectoryCB(traj_ptr);
00123
00124
00125 res.code.val = industrial_msgs::ServiceReturnCode::SUCCESS;
00126
00127 return true;
00128 }
00129
00130 void JointTrajectoryInterface::jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)
00131 {
00132 ROS_INFO("Receiving joint trajectory message");
00133
00134
00135 if (msg->points.empty())
00136 {
00137 ROS_INFO("Empty trajectory received, canceling current trajectory");
00138 trajectoryStop();
00139 return;
00140 }
00141
00142
00143 std::vector<SimpleMessage> robot_msgs;
00144 if (!trajectory_to_msgs(msg, &robot_msgs))
00145 return;
00146
00147
00148 send_to_robot(robot_msgs);
00149 }
00150
00151 bool JointTrajectoryInterface::trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr& traj, std::vector<SimpleMessage>* msgs)
00152 {
00153 msgs->clear();
00154
00155
00156 if (!is_valid(*traj))
00157 return false;
00158
00159 for (size_t i=0; i<traj->points.size(); ++i)
00160 {
00161 SimpleMessage msg;
00162 ros_JointTrajPt rbt_pt, xform_pt;
00163
00164
00165 if (!select(traj->joint_names, traj->points[i], this->all_joint_names_, &rbt_pt))
00166 return false;
00167
00168
00169 if (!transform(rbt_pt, &xform_pt))
00170 return false;
00171
00172
00173 if (!create_message(i, xform_pt, &msg))
00174 return false;
00175
00176 msgs->push_back(msg);
00177 }
00178
00179 return true;
00180 }
00181
00182 bool JointTrajectoryInterface::select(const std::vector<std::string>& ros_joint_names, const ros_JointTrajPt& ros_pt,
00183 const std::vector<std::string>& rbt_joint_names, ros_JointTrajPt* rbt_pt)
00184 {
00185 ROS_ASSERT(ros_joint_names.size() == ros_pt.positions.size());
00186
00187
00188 *rbt_pt = ros_pt;
00189 rbt_pt->positions.clear(); rbt_pt->velocities.clear(); rbt_pt->accelerations.clear();
00190
00191 for (size_t rbt_idx=0; rbt_idx < rbt_joint_names.size(); ++rbt_idx)
00192 {
00193 bool is_empty = rbt_joint_names[rbt_idx].empty();
00194
00195
00196 size_t ros_idx = std::find(ros_joint_names.begin(), ros_joint_names.end(), rbt_joint_names[rbt_idx]) - ros_joint_names.begin();
00197 bool is_found = ros_idx < ros_joint_names.size();
00198
00199
00200 if (!is_empty && !is_found)
00201 {
00202 ROS_ERROR("Expected joint (%s) not found in JointTrajectory. Aborting command.", rbt_joint_names[rbt_idx].c_str());
00203 return false;
00204 }
00205
00206 if (is_empty)
00207 {
00208 if (!ros_pt.positions.empty()) rbt_pt->positions.push_back(default_joint_pos_);
00209 if (!ros_pt.velocities.empty()) rbt_pt->velocities.push_back(-1);
00210 if (!ros_pt.accelerations.empty()) rbt_pt->accelerations.push_back(-1);
00211 }
00212 else
00213 {
00214 if (!ros_pt.positions.empty()) rbt_pt->positions.push_back(ros_pt.positions[ros_idx]);
00215 if (!ros_pt.velocities.empty()) rbt_pt->velocities.push_back(ros_pt.velocities[ros_idx]);
00216 if (!ros_pt.accelerations.empty()) rbt_pt->accelerations.push_back(ros_pt.accelerations[ros_idx]);
00217 }
00218 }
00219 return true;
00220 }
00221
00222
00223
00224
00225
00226
00227
00228 bool JointTrajectoryInterface::calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity)
00229 {
00230 std::vector<double> vel_ratios;
00231
00232 ROS_ASSERT(all_joint_names_.size() == pt.positions.size());
00233
00234
00235 if (pt.velocities.empty())
00236 {
00237 ROS_WARN("Joint velocities unspecified. Using default/safe speed.");
00238 *rbt_velocity = default_vel_ratio_;
00239 return true;
00240 }
00241
00242 for (size_t i=0; i<all_joint_names_.size(); ++i)
00243 {
00244 const std::string &jnt_name = all_joint_names_[i];
00245
00246
00247 if (jnt_name.empty())
00248 vel_ratios.push_back(-1);
00249 else if (joint_vel_limits_.count(jnt_name) == 0)
00250 vel_ratios.push_back(-1);
00251 else
00252 vel_ratios.push_back( fabs(pt.velocities[i] / joint_vel_limits_[jnt_name]) );
00253 }
00254
00255
00256 int max_idx = std::max_element(vel_ratios.begin(), vel_ratios.end()) - vel_ratios.begin();
00257
00258 if (vel_ratios[max_idx] > 0)
00259 *rbt_velocity = vel_ratios[max_idx];
00260 else
00261 {
00262 ROS_WARN_ONCE("Joint velocity-limits unspecified. Using default velocity-ratio.");
00263 *rbt_velocity = default_vel_ratio_;
00264 }
00265
00266 if ( (*rbt_velocity < 0) || (*rbt_velocity > 1) )
00267 {
00268 ROS_WARN("computed velocity (%.1f %%) is out-of-range. Clipping to [0-100%%]", *rbt_velocity * 100);
00269 *rbt_velocity = std::min(1.0, std::max(0.0, *rbt_velocity));
00270 }
00271
00272 return true;
00273 }
00274
00275 bool JointTrajectoryInterface::calc_duration(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_duration)
00276 {
00277 std::vector<double> durations;
00278 double this_time = pt.time_from_start.toSec();
00279 static double last_time = 0;
00280
00281 if (this_time <= last_time)
00282 *rbt_duration = default_duration_;
00283 else
00284 *rbt_duration = this_time - last_time;
00285
00286 last_time = this_time;
00287
00288 return true;
00289 }
00290
00291 bool JointTrajectoryInterface::create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage *msg)
00292 {
00293 industrial::joint_data::JointData pos;
00294 ROS_ASSERT(pt.positions.size() <= (unsigned int)pos.getMaxNumJoints());
00295
00296 for (size_t i=0; i<pt.positions.size(); ++i)
00297 pos.setJoint(i, pt.positions[i]);
00298
00299
00300 double velocity, duration;
00301 if (!calc_velocity(pt, &velocity) || !calc_duration(pt, &duration))
00302 return false;
00303
00304 rbt_JointTrajPt msg_data;
00305 msg_data.init(seq, pos, velocity, duration);
00306
00307 JointTrajPtMessage jtp_msg;
00308 jtp_msg.init(msg_data);
00309
00310 return jtp_msg.toTopic(*msg);
00311 }
00312
00313 void JointTrajectoryInterface::trajectoryStop()
00314 {
00315 JointTrajPtMessage jMsg;
00316 SimpleMessage msg, reply;
00317
00318 ROS_INFO("Joint trajectory handler: entering stopping state");
00319 jMsg.setSequence(SpecialSeqValues::STOP_TRAJECTORY);
00320 jMsg.toRequest(msg);
00321 ROS_DEBUG("Sending stop command");
00322 this->connection_->sendAndReceiveMsg(msg, reply);
00323 }
00324
00325 bool JointTrajectoryInterface::stopMotionCB(industrial_msgs::StopMotion::Request &req,
00326 industrial_msgs::StopMotion::Response &res)
00327 {
00328 trajectoryStop();
00329
00330
00331 res.code.val = industrial_msgs::ServiceReturnCode::SUCCESS;
00332
00333 return true;
00334 }
00335
00336 bool JointTrajectoryInterface::is_valid(const trajectory_msgs::JointTrajectory &traj)
00337 {
00338 for (int i=0; i<traj.points.size(); ++i)
00339 {
00340 const trajectory_msgs::JointTrajectoryPoint &pt = traj.points[i];
00341
00342
00343 if (pt.positions.empty())
00344 ROS_ERROR_RETURN(false, "Validation failed: Missing position data for trajectory pt %d", i);
00345
00346
00347 for (int j=0; j<pt.velocities.size(); ++j)
00348 {
00349 std::map<std::string, double>::iterator max_vel = joint_vel_limits_.find(traj.joint_names[j]);
00350 if (max_vel == joint_vel_limits_.end()) continue;
00351
00352 if (std::abs(pt.velocities[j]) > max_vel->second)
00353 ROS_ERROR_RETURN(false, "Validation failed: Max velocity exceeded for trajectory pt %d, joint '%s'", i, traj.joint_names[j].c_str());
00354 }
00355
00356
00357 if ((i > 0) && (pt.time_from_start.toSec() == 0))
00358 ROS_ERROR_RETURN(false, "Validation failed: Missing valid timestamp data for trajectory pt %d", i);
00359 }
00360
00361 return true;
00362 }
00363
00364
00365 void JointTrajectoryInterface::jointStateCB(const sensor_msgs::JointStateConstPtr &msg)
00366 {
00367 this->cur_joint_pos_ = *msg;
00368 }
00369
00370 }
00371 }
00372