joint_trajectory_streamer.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, 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 "industrial_robot_client/joint_trajectory_streamer.h"
00033 
00034 using industrial::simple_message::SimpleMessage;
00035 
00036 namespace industrial_robot_client
00037 {
00038 namespace joint_trajectory_streamer
00039 {
00040 
00041 bool JointTrajectoryStreamer::init(SmplMsgConnection* connection, const std::vector<std::string> &joint_names,
00042                                    const std::map<std::string, double> &velocity_limits)
00043 {
00044   bool rtn = true;
00045 
00046   ROS_INFO("JointTrajectoryStreamer: init");
00047 
00048   rtn &= JointTrajectoryInterface::init(connection, joint_names, velocity_limits);
00049 
00050   this->mutex_.lock();
00051   this->current_point_ = 0;
00052   this->state_ = TransferStates::IDLE;
00053   this->streaming_thread_ =
00054       new boost::thread(boost::bind(&JointTrajectoryStreamer::streamingThread, this));
00055   ROS_INFO("Unlocking mutex");
00056   this->mutex_.unlock();
00057 
00058   return rtn;
00059 }
00060 
00061 JointTrajectoryStreamer::~JointTrajectoryStreamer()
00062 {
00063   delete this->streaming_thread_;
00064 }
00065 
00066 void JointTrajectoryStreamer::jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg)
00067 {
00068   ROS_INFO("Receiving joint trajectory message");
00069 
00070   // read current state value (should be atomic)
00071   int state = this->state_;
00072 
00073   ROS_DEBUG("Current state is: %d", state);
00074   if (TransferStates::IDLE != state)
00075   {
00076     if (msg->points.empty())
00077       ROS_INFO("Empty trajectory received, canceling current trajectory");
00078     else
00079       ROS_ERROR("Trajectory splicing not yet implemented, stopping current motion.");
00080 
00081         this->mutex_.lock();
00082     trajectoryStop();
00083         this->mutex_.unlock();
00084     return;
00085   }
00086 
00087   if (msg->points.empty())
00088   {
00089     ROS_INFO("Empty trajectory received while in IDLE state, nothing is done");
00090     return;
00091   }
00092 
00093   // calc new trajectory
00094   std::vector<JointTrajPtMessage> new_traj_msgs;
00095   if (!trajectory_to_msgs(msg, &new_traj_msgs))
00096     return;
00097 
00098   // send command messages to robot
00099   send_to_robot(new_traj_msgs);
00100 }
00101 
00102 bool JointTrajectoryStreamer::send_to_robot(const std::vector<JointTrajPtMessage>& messages)
00103 {
00104   ROS_INFO("Loading trajectory, setting state to streaming");
00105   this->mutex_.lock();
00106   {
00107     ROS_INFO("Executing trajectory of size: %d", (int)messages.size());
00108     this->current_traj_ = messages;
00109     this->current_point_ = 0;
00110     this->state_ = TransferStates::STREAMING;
00111     this->streaming_start_ = ros::Time::now();
00112   }
00113   this->mutex_.unlock();
00114 
00115   return true;
00116 }
00117 
00118 bool JointTrajectoryStreamer::trajectory_to_msgs(const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector<JointTrajPtMessage>* msgs)
00119 {
00120   // use base function to transform points
00121   if (!JointTrajectoryInterface::trajectory_to_msgs(traj, msgs))
00122     return false;
00123 
00124   // pad trajectory as required for minimum streaming buffer size
00125   if (!msgs->empty() && (msgs->size() < (size_t)min_buffer_size_))
00126   {
00127     ROS_DEBUG("Padding trajectory: current(%d) => minimum(%d)", (int)msgs->size(), min_buffer_size_);
00128     while (msgs->size() < (size_t)min_buffer_size_)
00129       msgs->push_back(msgs->back());
00130   }
00131 
00132   return true;
00133 }
00134 
00135 
00136 void JointTrajectoryStreamer::streamingThread()
00137 {
00138   JointTrajPtMessage jtpMsg;
00139   int connectRetryCount = 1;
00140 
00141   ROS_INFO("Starting joint trajectory streamer thread");
00142   while (ros::ok())
00143   {
00144     ros::Duration(0.005).sleep();
00145 
00146     // automatically re-establish connection, if required
00147     if (connectRetryCount-- > 0)
00148     {
00149       ROS_INFO("Connecting to robot motion server");
00150       this->connection_->makeConnect();
00151       ros::Duration(0.250).sleep();  // wait for connection
00152 
00153       if (this->connection_->isConnected())
00154         connectRetryCount = 0;
00155       else if (connectRetryCount <= 0)
00156       {
00157         ROS_ERROR("Timeout connecting to robot controller.  Send new motion command to retry.");
00158         this->state_ = TransferStates::IDLE;
00159       }
00160       continue;
00161     }
00162 
00163     this->mutex_.lock();
00164 
00165     SimpleMessage msg, reply;
00166         
00167     switch (this->state_)
00168     {
00169       case TransferStates::IDLE:
00170         ros::Duration(0.250).sleep();  //  slower loop while waiting for new trajectory
00171         break;
00172 
00173       case TransferStates::STREAMING:
00174         if (this->current_point_ >= (int)this->current_traj_.size())
00175         {
00176           ROS_INFO("Trajectory streaming complete, setting state to IDLE");
00177           this->state_ = TransferStates::IDLE;
00178           break;
00179         }
00180 
00181         if (!this->connection_->isConnected())
00182         {
00183           ROS_DEBUG("Robot disconnected.  Attempting reconnect...");
00184           connectRetryCount = 5;
00185           break;
00186         }
00187 
00188         jtpMsg = this->current_traj_[this->current_point_];
00189         jtpMsg.toRequest(msg);
00190             
00191         ROS_DEBUG("Sending joint trajectory point");
00192         if (this->connection_->sendAndReceiveMsg(msg, reply, false))
00193         {
00194           ROS_INFO("Point[%d of %d] sent to controller",
00195                    this->current_point_, (int)this->current_traj_.size());
00196           this->current_point_++;
00197         }
00198         else
00199           ROS_WARN("Failed sent joint point, will try again");
00200 
00201         break;
00202       default:
00203         ROS_ERROR("Joint trajectory streamer: unknown state");
00204         this->state_ = TransferStates::IDLE;
00205         break;
00206     }
00207 
00208     this->mutex_.unlock();
00209   }
00210 
00211   ROS_WARN("Exiting trajectory streamer thread");
00212 }
00213 
00214 void JointTrajectoryStreamer::trajectoryStop()
00215 {
00216   JointTrajectoryInterface::trajectoryStop();
00217 
00218   ROS_DEBUG("Stop command sent, entering idle mode");
00219   this->state_ = TransferStates::IDLE;
00220 }
00221 
00222 } //joint_trajectory_streamer
00223 } //industrial_robot_client
00224 


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Mon Oct 6 2014 00:55:19