$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_downloader.h" 00033 #include "simple_message/joint_traj_pt.h" 00034 #include "simple_message/messages/joint_traj_pt_message.h" 00035 #include "simple_message/smpl_msg_connection.h" 00036 #include "utils.h" 00037 00038 using namespace industrial::smpl_msg_connection; 00039 using namespace industrial::joint_data; 00040 using namespace industrial::joint_traj_pt; 00041 using namespace industrial::joint_traj_pt_message; 00042 using namespace industrial::simple_message; 00043 using namespace motoman::utils; 00044 00045 00046 namespace motoman 00047 { 00048 namespace joint_trajectory_downloader 00049 { 00050 JointTrajectoryDownloader::JointTrajectoryDownloader() 00051 { 00052 } 00053 00054 JointTrajectoryDownloader::JointTrajectoryDownloader(ros::NodeHandle &n, 00055 SmplMsgConnection* robotConnecton) : node_(n) 00056 { 00057 ROS_INFO("Constructor joint trajectory downloader node"); 00058 00059 this->sub_joint_trajectory_ = this->node_.subscribe("command", 00060 0, &JointTrajectoryDownloader::jointTrajectoryCB, this); 00061 this->robot_ = robotConnecton; 00062 ROS_INFO("Joint trajectory downloader node initialized"); 00063 } 00064 00065 JointTrajectoryDownloader::~JointTrajectoryDownloader() 00066 { 00067 trajectoryStop(); 00068 this->sub_joint_trajectory_.shutdown(); 00069 } 00070 00071 void JointTrajectoryDownloader::jointTrajectoryCB( 00072 const trajectory_msgs::JointTrajectoryConstPtr &msg) 00073 { 00074 ROS_INFO("Receiving joint trajectory message"); 00075 00076 00077 if (!checkTrajectory(msg)) 00078 { 00079 ROS_ERROR("Joint trajectory check failed, trajectory not downloaded"); 00080 return; 00081 } 00082 00083 std::vector<double> joint_velocity_limits; 00084 if (!getVelocityLimits("robot_description", msg, joint_velocity_limits)) 00085 { 00086 ROS_ERROR("Failed to get joint velocity limits"); 00087 return; 00088 } 00089 00090 00091 00092 for (int i = 0; i < msg->points.size(); i++) 00093 { 00094 ROS_INFO("Sending joints trajectory point[%d]", i); 00095 00096 JointTrajPt jPt; 00097 JointTrajPtMessage jMsg; 00098 SimpleMessage topic; 00099 trajectory_msgs::JointTrajectoryPoint pt; 00100 00101 pt = msg->points[i]; 00102 00103 // Performing a manual copy of the joint velocities in order to send them 00104 // to the utility function. Passing the pt data members doesn't seem to 00105 // work. 00106 std::vector<double> joint_velocities; 00107 double velocity =0 ; 00108 00109 joint_velocities.resize(msg->joint_names.size()); 00110 for (int j = 0; j < joint_velocities.size(); j++) 00111 { 00112 joint_velocities[i] = pt.velocities[i]; 00113 } 00114 velocity = toMotomanVelocity(joint_velocity_limits, joint_velocities); 00115 00116 jPt.setVelocity(velocity); 00117 00118 // The first and last sequence values must be given a special sequence 00119 // value 00120 if (0 == i) 00121 { 00122 ROS_DEBUG("First trajectory point, setting special sequence value"); 00123 jPt.setSequence(SpecialSeqValues::START_TRAJECTORY_DOWNLOAD); 00124 } 00125 else if (msg->points.size() - 1 == i) 00126 { 00127 ROS_DEBUG("Last trajectory point, setting special sequence value"); 00128 jPt.setSequence(SpecialSeqValues::END_TRAJECTORY); 00129 } 00130 else 00131 { 00132 jPt.setSequence(i); 00133 } 00134 00135 // Copy position data to local variable 00136 JointData data; 00137 for (int j = 0; j < msg->joint_names.size(); j++) 00138 { 00139 pt = msg->points[j]; 00140 data.setJoint(j, pt.positions[j]); 00141 } 00142 00143 // Initialize joint trajectory message 00144 jPt.setJointPosition(data); 00145 00146 jMsg.init(jPt); 00147 jMsg.toTopic(topic); 00148 00149 ROS_DEBUG("Sending joint trajectory point"); 00150 if (this->robot_->sendMsg(topic)) 00151 { 00152 ROS_INFO("Point[%d] sent to controller", i); 00153 } 00154 else 00155 { 00156 ROS_WARN("Failed sent joint point, skipping point"); 00157 } 00158 } 00159 } 00160 00161 void JointTrajectoryDownloader::trajectoryStop() 00162 { 00163 JointTrajPtMessage jMsg; 00164 SimpleMessage msg; 00165 SimpleMessage reply; 00166 00167 ROS_INFO("Joint trajectory downloader: entering stopping state"); 00168 jMsg.point_.setSequence(SpecialSeqValues::STOP_TRAJECTORY); 00169 jMsg.toRequest(msg); 00170 ROS_DEBUG("Sending stop command"); 00171 this->robot_->sendAndReceiveMsg(msg, reply); 00172 ROS_DEBUG("Stop command sent"); 00173 } 00174 00175 } //joint_trajectory_handler 00176 } //motoman 00177