$search
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 "joint_trajectory_handler.h" 00033 #include "simple_message/messages/joint_message.h" 00034 #include "simple_message/smpl_msg_connection.h" 00035 00036 using namespace industrial::smpl_msg_connection; 00037 using namespace industrial::joint_message; 00038 using namespace industrial::simple_message; 00039 00040 namespace motoman 00041 { 00042 namespace joint_trajectory_handler 00043 { 00044 JointTrajectoryHandler::JointTrajectoryHandler() 00045 { 00046 } 00047 00048 JointTrajectoryHandler::JointTrajectoryHandler(ros::NodeHandle &n, SmplMsgConnection* robotConnecton) : 00049 node_(n) 00050 { 00051 ROS_INFO("Constructor joint trajectory handler node"); 00052 00053 this->mutex_.lock(); 00054 this->sub_joint_tranectory_ = this->node_.subscribe("command", 0, &JointTrajectoryHandler::jointTrajectoryCB, 00055 this); 00056 this->robot_ = robotConnecton; 00057 this->currentPoint = 0; 00058 this->state_ = JointTrajectoryStates::IDLE; 00059 this->trajectoryHandler_ = 00060 new boost::thread(boost::bind(&JointTrajectoryHandler::trajectoryHandler, this)); 00061 ROS_INFO("Unlocking mutex"); 00062 this->mutex_.unlock(); 00063 } 00064 00065 JointTrajectoryHandler::~JointTrajectoryHandler() 00066 { 00067 trajectoryStop(); 00068 this->sub_joint_tranectory_.shutdown(); 00069 delete this->trajectoryHandler_; 00070 } 00071 00072 void JointTrajectoryHandler::jointTrajectoryCB(const trajectory_msgs::JointTrajectoryConstPtr &msg) 00073 { 00074 ROS_INFO("Receiving joint trajctory message"); 00075 this->mutex_.lock(); 00076 ROS_INFO("Processing joint trajctory message (mutex acquired)"); 00077 ROS_DEBUG("Current state is: %d", this->state_); 00078 if (JointTrajectoryStates::IDLE != this->state_) 00079 { 00080 if (msg->points.empty()) 00081 { 00082 ROS_INFO("Empty trajectory received, canceling current trajectory"); 00083 } 00084 else 00085 { 00086 ROS_ERROR("Trajectory splicing not yet implemented, stopping current motion."); 00087 } 00088 trajectoryStop(); 00089 } 00090 else 00091 { 00092 if (msg->points.empty()) 00093 { 00094 ROS_INFO("Empty trajectory received while in IDLE state, nothing is done"); 00095 } 00096 else 00097 { 00098 ROS_INFO("Loading trajectory, setting state to streaming"); 00099 this->current_traj_ = *msg; 00100 00101 // TODO: This section pads any trajectory below the minimum size with the same 00102 // end point. This is required because the motoman side requires a minimum buffer 00103 // size before it start motion. 00104 while (current_traj_.points.size() < 6) 00105 { 00106 ROS_DEBUG("Padding trajectory, current size: %d", current_traj_.points.size()); 00107 current_traj_.points.push_back(current_traj_.points[current_traj_.points.size()-1]); 00108 }; 00109 00110 ROS_INFO("Executing trajectory of size: %d", this->current_traj_.points.size()); 00111 this->currentPoint = 0; 00112 this->state_ = JointTrajectoryStates::STREAMING; 00113 } 00114 } 00115 this->mutex_.unlock(); 00116 } 00117 00118 void JointTrajectoryHandler::trajectoryHandler() 00119 { 00120 JointMessage jMsg; 00121 SimpleMessage msg; 00122 SimpleMessage reply; 00123 trajectory_msgs::JointTrajectoryPoint pt; 00124 ROS_INFO("Starting joint trajectory handler state"); 00125 while (ros::ok()) 00126 { 00127 this->mutex_.lock(); 00128 00129 if (this->robot_->isConnected()) 00130 { 00131 00132 //TODO: These variables should be moved outside of this loop 00133 //so that we aren't contantly reinitializing them. 00134 JointMessage jMsg; 00135 SimpleMessage msg; 00136 SimpleMessage reply; 00137 trajectory_msgs::JointTrajectoryPoint pt; 00138 switch (this->state_) 00139 { 00140 case JointTrajectoryStates::IDLE: 00141 ros::Duration(0.250).sleep(); 00142 break; 00143 00144 00145 case JointTrajectoryStates::STREAMING: 00146 if (this->currentPoint < this->current_traj_.points.size()) 00147 { 00148 ROS_INFO("Streaming joints point[%d]", this->currentPoint); 00149 pt = this->current_traj_.points[this->currentPoint]; 00150 00151 jMsg.setSequence(this->currentPoint); 00152 00153 for (int i = 0; i < this->current_traj_.joint_names.size(); i++) 00154 { 00155 jMsg.getJoints().setJoint(i, pt.positions[i]); 00156 } 00157 00158 jMsg.toRequest(msg); 00159 ROS_DEBUG("Sending joint point"); 00160 if (this->robot_->sendAndReceiveMsg(msg, reply)) 00161 { 00162 ROS_INFO("Point[%d] sent to controller", this->currentPoint); 00163 this->currentPoint++; 00164 } 00165 else 00166 { 00167 ROS_WARN("Failed sent joint point, will try again"); 00168 } 00169 } 00170 else 00171 { 00172 ROS_INFO("Trajectory streaming complete, setting state to IDLE"); 00173 this->state_ = JointTrajectoryStates::IDLE; 00174 } 00175 break; 00176 00177 default: 00178 ROS_ERROR("Joint trajectory handler: unknown state"); 00179 this->state_ = JointTrajectoryStates::IDLE; 00180 break; 00181 } 00182 00183 } 00184 else 00185 { 00186 ROS_INFO("Connecting to robot motion server"); 00187 this->robot_->makeConnect(); 00188 } 00189 00190 this->mutex_.unlock(); 00191 ros::Duration(0.005).sleep(); 00192 } 00193 00194 ROS_WARN("Exiting trajectory handler thread"); 00195 } 00196 00197 00198 00199 void JointTrajectoryHandler::trajectoryStop() 00200 { 00201 JointMessage jMsg; 00202 SimpleMessage msg; 00203 SimpleMessage reply; 00204 00205 ROS_INFO("Joint trajectory handler: entering stopping state"); 00206 jMsg.setSequence(SpecialSeqValues::STOP_TRAJECTORY); 00207 jMsg.toRequest(msg); 00208 ROS_DEBUG("Sending stop command"); 00209 this->robot_->sendAndReceiveMsg(msg, reply); 00210 ROS_DEBUG("Stop command sent, entring idle mode"); 00211 this->state_ = JointTrajectoryStates::IDLE; 00212 } 00213 00214 00215 00216 00217 00218 } //joint_trajectory_handler 00219 } //motoman 00220