Go to the documentation of this file.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 "fs100/industrial_robot_client/joint_trajectory_streamer.h"
00033
00034 using namespace industrial::simple_message;
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
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
00094 std::vector<SimpleMessage> new_traj_msgs;
00095 if (!trajectory_to_msgs(msg, &new_traj_msgs))
00096 return;
00097
00098
00099 send_to_robot(new_traj_msgs);
00100 }
00101
00102 bool JointTrajectoryStreamer::send_to_robot(const std::vector<SimpleMessage>& 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<SimpleMessage>* msgs)
00119 {
00120
00121 if (!JointTrajectoryInterface::trajectory_to_msgs(traj, msgs))
00122 return false;
00123
00124
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 int connectRetryCount = 1;
00139
00140 ROS_INFO("Starting joint trajectory streamer thread");
00141 while (ros::ok())
00142 {
00143 ros::Duration(0.005).sleep();
00144
00145
00146 if (connectRetryCount-- > 0)
00147 {
00148 ROS_INFO("Connecting to robot motion server");
00149 this->connection_->makeConnect();
00150 ros::Duration(0.250).sleep();
00151
00152 if (this->connection_->isConnected())
00153 connectRetryCount = 0;
00154 else if (connectRetryCount <= 0)
00155 {
00156 ROS_ERROR("Timeout connecting to robot controller. Send new motion command to retry.");
00157 this->state_ = TransferStates::IDLE;
00158 }
00159 continue;
00160 }
00161
00162 this->mutex_.lock();
00163
00164 SimpleMessage msg, tmpMsg, reply;
00165
00166 switch (this->state_)
00167 {
00168 case TransferStates::IDLE:
00169 ros::Duration(0.250).sleep();
00170 break;
00171
00172 case TransferStates::STREAMING:
00173 if (this->current_point_ >= (int)this->current_traj_.size())
00174 {
00175 ROS_INFO("Trajectory streaming complete, setting state to IDLE");
00176 this->state_ = TransferStates::IDLE;
00177 break;
00178 }
00179
00180 if (!this->connection_->isConnected())
00181 {
00182 ROS_DEBUG("Robot disconnected. Attempting reconnect...");
00183 connectRetryCount = 5;
00184 break;
00185 }
00186
00187 tmpMsg = this->current_traj_[this->current_point_];
00188 msg.init(tmpMsg.getMessageType(), CommTypes::SERVICE_REQUEST,
00189 ReplyTypes::INVALID, tmpMsg.getData());
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 }
00223 }
00224