joint_trajectory_streamer.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2013, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *  * Redistributions of source code must retain the above copyright
00011  *  notice, this list of conditions and the following disclaimer.
00012  *  * Redistributions in binary form must reproduce the above copyright
00013  *  notice, this list of conditions and the following disclaimer in the
00014  *  documentation and/or other materials provided with the distribution.
00015  *  * Neither the name of the Southwest Research Institute, nor the names
00016  *  of its contributors may be used to endorse or promote products derived
00017  *  from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #include "motoman_driver/joint_trajectory_streamer.h"
00033 #include "motoman_driver/simple_message/motoman_motion_reply_message.h"
00034 #include "simple_message/messages/joint_traj_pt_full_message.h"
00035 #include "motoman_driver/simple_message/messages/joint_traj_pt_full_ex_message.h"
00036 #include "industrial_robot_client/utils.h"
00037 #include "industrial_utils/param_utils.h"
00038 #include <map>
00039 #include <vector>
00040 #include <string>
00041 
00042 namespace CommTypes = industrial::simple_message::CommTypes;
00043 namespace ReplyTypes = industrial::simple_message::ReplyTypes;
00044 using industrial::joint_data::JointData;
00045 using industrial::joint_traj_pt_full::JointTrajPtFull;
00046 using industrial::joint_traj_pt_full_message::JointTrajPtFullMessage;
00047 using industrial::joint_traj_pt_full_ex::JointTrajPtFullEx;
00048 using industrial::joint_traj_pt_full_ex_message::JointTrajPtFullExMessage;
00049 
00050 using motoman::simple_message::motion_reply_message::MotionReplyMessage;
00051 namespace TransferStates = industrial_robot_client::joint_trajectory_streamer::TransferStates;
00052 namespace MotionReplyResults = motoman::simple_message::motion_reply::MotionReplyResults;
00053 
00054 namespace motoman
00055 {
00056 namespace joint_trajectory_streamer
00057 {
00058 
00059 namespace
00060 {
00061   const double pos_stale_time_ = 1.0;  // max time since last "current position" update, for validation (sec)
00062   const double start_pos_tol_  = 1e-4;  // max difference btwn start & current position, for validation (rad)
00063 }
00064 
00065 #define ROS_ERROR_RETURN(rtn,...) do {ROS_ERROR(__VA_ARGS__); return(rtn);} while(0)
00066 
00067 // override init() to read "robot_id" parameter and subscribe to joint_states
00068 bool MotomanJointTrajectoryStreamer::init(SmplMsgConnection* connection, const std::map<int, RobotGroup> &robot_groups,
00069     const std::map<std::string, double> &velocity_limits)
00070 {
00071   bool rtn = true;
00072 
00073   ROS_INFO("MotomanJointTrajectoryStreamer: init");
00074 
00075   this->robot_groups_ = robot_groups;
00076   rtn &= JointTrajectoryStreamer::init(connection, robot_groups, velocity_limits);
00077 
00078   motion_ctrl_.init(connection, 0);
00079   for (int i = 0; i < robot_groups_.size(); i++)
00080   {
00081     MotomanMotionCtrl motion_ctrl;
00082 
00083     int robot_id = robot_groups_[i].get_group_id();
00084     rtn &= motion_ctrl.init(connection, robot_id);
00085 
00086     motion_ctrl_map_[robot_id] = motion_ctrl;
00087   }
00088 
00089   disabler_ = node_.advertiseService("/robot_disable", &MotomanJointTrajectoryStreamer::disableRobotCB, this);
00090 
00091   enabler_ = node_.advertiseService("/robot_enable", &MotomanJointTrajectoryStreamer::enableRobotCB, this);
00092 
00093   return rtn;
00094 }
00095 
00096 // override init() to read "robot_id" parameter and subscribe to joint_states
00097 bool MotomanJointTrajectoryStreamer::init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00098     const std::map<std::string, double> &velocity_limits)
00099 {
00100   bool rtn = true;
00101 
00102   ROS_INFO("MotomanJointTrajectoryStreamer: init");
00103 
00104   rtn &= JointTrajectoryStreamer::init(connection, joint_names, velocity_limits);
00105 
00106   // try to read robot_id parameter, if none specified
00107   if ((robot_id_ < 0))
00108     node_.param("robot_id", robot_id_, 0);
00109 
00110   rtn &= motion_ctrl_.init(connection, robot_id_);
00111 
00112   disabler_ = node_.advertiseService("/robot_disable", &MotomanJointTrajectoryStreamer::disableRobotCB, this);
00113 
00114   enabler_ = node_.advertiseService("/robot_enable", &MotomanJointTrajectoryStreamer::enableRobotCB, this);
00115 
00116   return rtn;
00117 }
00118 
00119 MotomanJointTrajectoryStreamer::~MotomanJointTrajectoryStreamer()
00120 {
00121   //TODO Find better place to call StopTrajMode
00122   motion_ctrl_.setTrajMode(false);   // release TrajMode, so INFORM jobs can run
00123 }
00124 
00125 bool MotomanJointTrajectoryStreamer::disableRobotCB(std_srvs::Trigger::Request &req,
00126                                            std_srvs::Trigger::Response &res)
00127 {
00128 
00129   trajectoryStop();
00130 
00131   bool ret = motion_ctrl_.setTrajMode(false);  
00132   res.success = ret;
00133   
00134   if (!res.success) {
00135     res.message="Motoman robot was NOT disabled. Please re-examine and retry.";
00136     ROS_ERROR_STREAM(res.message);
00137   }
00138   else {
00139     res.message="Motoman robot is now disabled and will NOT accept motion commands.";
00140     ROS_WARN_STREAM(res.message);
00141   }
00142     
00143 
00144   return true;
00145 
00146 }
00147 
00148 bool MotomanJointTrajectoryStreamer::enableRobotCB(std_srvs::Trigger::Request &req,
00149                                                    std_srvs::Trigger::Response &res)
00150 {
00151   bool ret = motion_ctrl_.setTrajMode(true);  
00152   res.success = ret;
00153   
00154   if (!res.success) {
00155     res.message="Motoman robot was NOT enabled. Please re-examine and retry.";
00156     ROS_ERROR_STREAM(res.message);
00157   }
00158   else {
00159     res.message="Motoman robot is now enabled and will accept motion commands.";
00160     ROS_WARN_STREAM(res.message);
00161   }
00162 
00163   return true;
00164 
00165 }
00166 
00167 
00168   
00169 // override create_message to generate JointTrajPtFull message (instead of default JointTrajPt)
00170 bool MotomanJointTrajectoryStreamer::create_message(int seq, const trajectory_msgs::JointTrajectoryPoint &pt, SimpleMessage *msg)
00171 {
00172   JointTrajPtFull msg_data;
00173   JointData values;
00174 
00175   // copy position data
00176   if (!pt.positions.empty())
00177   {
00178     if (VectorToJointData(pt.positions, values))
00179       msg_data.setPositions(values);
00180     else
00181       ROS_ERROR_RETURN(false, "Failed to copy position data to JointTrajPtFullMessage");
00182   }
00183   else
00184     msg_data.clearPositions();
00185 
00186   // copy velocity data
00187   if (!pt.velocities.empty())
00188   {
00189     if (VectorToJointData(pt.velocities, values))
00190       msg_data.setVelocities(values);
00191     else
00192       ROS_ERROR_RETURN(false, "Failed to copy velocity data to JointTrajPtFullMessage");
00193   }
00194   else
00195     msg_data.clearVelocities();
00196 
00197   // copy acceleration data
00198   if (!pt.accelerations.empty())
00199   {
00200     if (VectorToJointData(pt.accelerations, values))
00201       msg_data.setAccelerations(values);
00202     else
00203       ROS_ERROR_RETURN(false, "Failed to copy acceleration data to JointTrajPtFullMessage");
00204   }
00205   else
00206     msg_data.clearAccelerations();
00207 
00208   // copy scalar data
00209   msg_data.setRobotID(robot_id_);
00210   msg_data.setSequence(seq);
00211   msg_data.setTime(pt.time_from_start.toSec());
00212 
00213 
00214   // convert to message
00215   JointTrajPtFullMessage jtpf_msg;
00216   jtpf_msg.init(msg_data);
00217 
00218   return jtpf_msg.toRequest(*msg);  // assume "request" COMM_TYPE for now
00219 }
00220 
00221 bool MotomanJointTrajectoryStreamer::create_message_ex(int seq, const motoman_msgs::DynamicJointPoint &point, SimpleMessage *msg)
00222 {
00223   JointTrajPtFullEx msg_data_ex;
00224   JointTrajPtFullExMessage jtpf_msg_ex;
00225   std::vector<industrial::joint_traj_pt_full::JointTrajPtFull> msg_data_vector;
00226 
00227   JointData values;
00228 
00229   int num_groups = point.num_groups;
00230 
00231   for (int i = 0; i < num_groups; i++)
00232   {
00233     JointTrajPtFull msg_data;
00234 
00235     motoman_msgs::DynamicJointsGroup pt;
00236 
00237     motoman_msgs::DynamicJointPoint dpoint;
00238 
00239     pt = point.groups[i];
00240 
00241     if (pt.positions.size() < 10)
00242     {
00243       int size_to_complete = 10 - pt.positions.size();
00244 
00245       std::vector<double> positions(size_to_complete, 0.0);
00246       std::vector<double> velocities(size_to_complete, 0.0);
00247       std::vector<double> accelerations(size_to_complete, 0.0);
00248 
00249       pt.positions.insert(pt.positions.end(), positions.begin(), positions.end());
00250       pt.velocities.insert(pt.velocities.end(), velocities.begin(), velocities.end());
00251       pt.accelerations.insert(pt.accelerations.end(), accelerations.begin(), accelerations.end());
00252     }
00253 
00254     // copy position data
00255     if (!pt.positions.empty())
00256     {
00257       if (VectorToJointData(pt.positions, values))
00258         msg_data.setPositions(values);
00259       else
00260         ROS_ERROR_RETURN(false, "Failed to copy position data to JointTrajPtFullMessage");
00261     }
00262     else
00263       msg_data.clearPositions();
00264     // copy velocity data
00265     if (!pt.velocities.empty())
00266     {
00267       if (VectorToJointData(pt.velocities, values))
00268         msg_data.setVelocities(values);
00269       else
00270         ROS_ERROR_RETURN(false, "Failed to copy velocity data to JointTrajPtFullMessage");
00271     }
00272     else
00273       msg_data.clearVelocities();
00274 
00275     // copy acceleration data
00276     if (!pt.accelerations.empty())
00277     {
00278       if (VectorToJointData(pt.accelerations, values))
00279         msg_data.setAccelerations(values);
00280       else
00281         ROS_ERROR_RETURN(false, "Failed to copy acceleration data to JointTrajPtFullMessage");
00282     }
00283     else
00284       msg_data.clearAccelerations();
00285 
00286     // copy scalar data
00287     msg_data.setRobotID(pt.group_number);
00288     msg_data.setSequence(seq);
00289     msg_data.setTime(pt.time_from_start.toSec());
00290 
00291     // convert to message
00292     msg_data_vector.push_back(msg_data);
00293   }
00294 
00295   msg_data_ex.setMultiJointTrajPtData(msg_data_vector);
00296   msg_data_ex.setNumGroups(num_groups);
00297   msg_data_ex.setSequence(seq);
00298   jtpf_msg_ex.init(msg_data_ex);
00299 
00300   return jtpf_msg_ex.toRequest(*msg);  // assume "request" COMM_TYPE for now
00301 }
00302 
00303 bool MotomanJointTrajectoryStreamer::create_message(int seq, const motoman_msgs::DynamicJointsGroup &pt, SimpleMessage *msg)
00304 {
00305   JointTrajPtFull msg_data;
00306   JointData values;
00307   // copy position data
00308   if (!pt.positions.empty())
00309   {
00310     if (VectorToJointData(pt.positions, values))
00311       msg_data.setPositions(values);
00312     else
00313       ROS_ERROR_RETURN(false, "Failed to copy position data to JointTrajPtFullMessage");
00314   }
00315   else
00316     msg_data.clearPositions();
00317 
00318   // copy velocity data
00319   if (!pt.velocities.empty())
00320   {
00321     if (VectorToJointData(pt.velocities, values))
00322       msg_data.setVelocities(values);
00323     else
00324       ROS_ERROR_RETURN(false, "Failed to copy velocity data to JointTrajPtFullMessage");
00325   }
00326   else
00327     msg_data.clearVelocities();
00328 
00329   // copy acceleration data
00330   if (!pt.accelerations.empty())
00331   {
00332     if (VectorToJointData(pt.accelerations, values))
00333       msg_data.setAccelerations(values);
00334     else
00335       ROS_ERROR_RETURN(false, "Failed to copy acceleration data to JointTrajPtFullMessage");
00336   }
00337   else
00338     msg_data.clearAccelerations();
00339 
00340   // copy scalar data
00341   msg_data.setRobotID(pt.group_number);
00342 
00343   msg_data.setSequence(seq);
00344   msg_data.setTime(pt.time_from_start.toSec());
00345 
00346   // convert to message
00347   JointTrajPtFullMessage jtpf_msg;
00348   jtpf_msg.init(msg_data);
00349 
00350   return jtpf_msg.toRequest(*msg);  // assume "request" COMM_TYPE for now
00351 }
00352 
00353 bool MotomanJointTrajectoryStreamer::VectorToJointData(const std::vector<double> &vec,
00354     JointData &joints)
00355 {
00356   if (vec.size() > joints.getMaxNumJoints())
00357     ROS_ERROR_RETURN(false, "Failed to copy to JointData.  Len (%d) out of range (0 to %d)",
00358                      (int)vec.size(), joints.getMaxNumJoints());
00359 
00360   joints.init();
00361   for (int i = 0; i < vec.size(); ++i)
00362   {
00363     joints.setJoint(i, vec[i]);
00364   }
00365   return true;
00366 }
00367   
00368 // override send_to_robot to provide controllerReady() and setTrajMode() calls
00369 bool MotomanJointTrajectoryStreamer::send_to_robot(const std::vector<SimpleMessage>& messages)
00370 {
00371   if (!motion_ctrl_.controllerReady())
00372     ROS_ERROR_RETURN(false, "Failed to initialize MotoRos motion, so trajectory ABORTED.\n If safe, call /robot_enable service to (re-)enable Motoplus motion.");
00373 
00374   return JointTrajectoryStreamer::send_to_robot(messages);
00375 }
00376 
00377 // override streamingThread, to provide check/retry of MotionReply.result=BUSY
00378 void MotomanJointTrajectoryStreamer::streamingThread()
00379 {
00380   int connectRetryCount = 1;
00381 
00382   ROS_INFO("Starting Motoman joint trajectory streamer thread");
00383   while (ros::ok())
00384   {
00385     ros::Duration(0.005).sleep();
00386 
00387     // automatically re-establish connection, if required
00388     if (connectRetryCount-- > 0)
00389     {
00390       ROS_INFO("Connecting to robot motion server");
00391       this->connection_->makeConnect();
00392       ros::Duration(0.250).sleep();  // wait for connection
00393 
00394       if (this->connection_->isConnected())
00395         connectRetryCount = 0;
00396       else if (connectRetryCount <= 0)
00397       {
00398         ROS_ERROR("Timeout connecting to robot controller.  Send new motion command to retry.");
00399         this->state_ = TransferStates::IDLE;
00400       }
00401       continue;
00402     }
00403 
00404     this->mutex_.lock();
00405 
00406     SimpleMessage msg, tmpMsg, reply;
00407 
00408     switch (this->state_)
00409     {
00410     case TransferStates::IDLE:
00411       ros::Duration(0.250).sleep();  //  slower loop while waiting for new trajectory
00412       break;
00413 
00414     case TransferStates::STREAMING:
00415       if (this->current_point_ >= static_cast<int>(this->current_traj_.size()))
00416       {
00417         ROS_INFO("Trajectory streaming complete, setting state to IDLE");
00418         this->state_ = TransferStates::IDLE;
00419         break;
00420       }
00421 
00422       if (!this->connection_->isConnected())
00423       {
00424         ROS_DEBUG("Robot disconnected.  Attempting reconnect...");
00425         connectRetryCount = 5;
00426         break;
00427       }
00428 
00429       tmpMsg = this->current_traj_[this->current_point_];
00430       msg.init(tmpMsg.getMessageType(), CommTypes::SERVICE_REQUEST,
00431                ReplyTypes::INVALID, tmpMsg.getData());  // set commType=REQUEST
00432 
00433       if (!this->connection_->sendAndReceiveMsg(msg, reply, false))
00434         ROS_WARN("Failed sent joint point, will try again");
00435       else
00436       {
00437         MotionReplyMessage reply_status;
00438         if (!reply_status.init(reply))
00439         {
00440           ROS_ERROR("Aborting trajectory: Unable to parse JointTrajectoryPoint reply");
00441           this->state_ = TransferStates::IDLE;
00442           break;
00443         }
00444 
00445         if (reply_status.reply_.getResult() == MotionReplyResults::SUCCESS)
00446         {
00447           ROS_DEBUG("Point[%d of %d] sent to controller",
00448                     this->current_point_, static_cast<int>(this->current_traj_.size()));
00449           this->current_point_++;
00450         }
00451         else if (reply_status.reply_.getResult() == MotionReplyResults::BUSY)
00452           break;  // silently retry sending this point
00453         else
00454         {
00455           ROS_ERROR_STREAM("Aborting Trajectory.  Failed to send point"
00456                            << " (#" << this->current_point_ << "): "
00457                            << MotomanMotionCtrl::getErrorString(reply_status.reply_));
00458           this->state_ = TransferStates::IDLE;
00459           break;
00460         }
00461       }
00462       break;
00463     default:
00464       ROS_ERROR("Joint trajectory streamer: unknown state");
00465       this->state_ = TransferStates::IDLE;
00466       break;
00467     }
00468     this->mutex_.unlock();
00469   }
00470   ROS_WARN("Exiting trajectory streamer thread");
00471 }
00472 
00473 // override trajectoryStop to send MotionCtrl message
00474 void MotomanJointTrajectoryStreamer::trajectoryStop()
00475 {
00476   this->state_ = TransferStates::IDLE;  // stop sending trajectory points
00477   motion_ctrl_.stopTrajectory();
00478 }
00479 
00480 // override is_valid to include FS100-specific checks
00481 bool MotomanJointTrajectoryStreamer::is_valid(const trajectory_msgs::JointTrajectory &traj)
00482 {
00483   if (!JointTrajectoryInterface::is_valid(traj))
00484     return false;
00485 
00486   for (int i = 0; i < traj.points.size(); ++i)
00487   {
00488     const trajectory_msgs::JointTrajectoryPoint &pt = traj.points[i];
00489 
00490     // FS100 requires valid velocity data
00491     if (pt.velocities.empty())
00492       ROS_ERROR_RETURN(false, "Validation failed: Missing velocity data for trajectory pt %d", i);
00493   }
00494 
00495   if ((cur_joint_pos_.header.stamp - ros::Time::now()).toSec() > pos_stale_time_)
00496     ROS_ERROR_RETURN(false, "Validation failed: Can't get current robot position.");
00497 
00498   // FS100 requires trajectory start at current position
00499   namespace IRC_utils = industrial_robot_client::utils;
00500   if (!IRC_utils::isWithinRange(cur_joint_pos_.name, cur_joint_pos_.position,
00501                                 traj.joint_names, traj.points[0].positions,
00502                                 start_pos_tol_))
00503   {
00504     ROS_ERROR_RETURN(false, "Validation failed: Trajectory doesn't start at current position.");
00505   }
00506   return true;
00507 }
00508 
00509 bool MotomanJointTrajectoryStreamer::is_valid(const motoman_msgs::DynamicJointTrajectory &traj)
00510 {
00511   if (!JointTrajectoryInterface::is_valid(traj))
00512     return false;
00513   ros::Time time_stamp;
00514   int group_number;
00515   for (int i = 0; i < traj.points.size(); ++i)
00516   {
00517     for (int gr = 0; gr < traj.points[i].num_groups; gr++)
00518     {
00519       const motoman_msgs::DynamicJointsGroup &pt = traj.points[i].groups[gr];
00520       time_stamp = cur_joint_pos_map_[pt.group_number].header.stamp;
00521       //TODO: adjust for more joints
00522       group_number = pt.group_number;
00523       // FS100 requires valid velocity data
00524       if (pt.velocities.empty())
00525         ROS_ERROR_RETURN(false, "Validation failed: Missing velocity data for trajectory pt %d", i);
00526 
00527       // FS100 requires trajectory start at current position
00528       namespace IRC_utils = industrial_robot_client::utils;
00529 
00530       if (!IRC_utils::isWithinRange(cur_joint_pos_map_[group_number].name, cur_joint_pos_map_[group_number].position,
00531                                     traj.joint_names, traj.points[0].groups[gr].positions,
00532                                     start_pos_tol_))
00533       {
00534         ROS_ERROR_RETURN(false, "Validation failed: Trajectory doesn't start at current position.");
00535       }
00536     }
00537   }
00538 
00539   if ((time_stamp - ros::Time::now()).toSec() > pos_stale_time_)
00540     ROS_ERROR_RETURN(false, "Validation failed: Can't get current robot position.");
00541 
00542   return true;
00543 }
00544 
00545 }  // namespace joint_trajectory_streamer
00546 }  // namespace motoman
00547 


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:57