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 <dx100/joint_trajectory_downloader.h>
00033 #include "dx100/trajectory_job.h"
00034 #include "simple_message/joint_traj.h"
00035 #include "simple_message/joint_traj_pt.h"
00036 #include "simple_message/messages/joint_traj_pt_message.h"
00037 #include "simple_message/smpl_msg_connection.h"
00038 #include <dx100/utils.h>
00039
00040 #include <fstream>
00041
00042 using namespace industrial::smpl_msg_connection;
00043 using namespace industrial::joint_data;
00044 using namespace industrial::joint_traj;
00045 using namespace industrial::joint_traj_pt;
00046 using namespace industrial::joint_traj_pt_message;
00047 using namespace industrial::simple_message;
00048 using namespace motoman::utils;
00049 using namespace motoman::trajectory_job;
00050
00051
00052 #define GENERATE_LOCAL_JOB_FILE
00053
00054 namespace motoman
00055 {
00056 namespace joint_trajectory_downloader
00057 {
00058 JointTrajectoryDownloader::JointTrajectoryDownloader()
00059 {
00060 }
00061
00062 JointTrajectoryDownloader::JointTrajectoryDownloader(ros::NodeHandle &n,
00063 SmplMsgConnection* robotConnecton) : node_(n)
00064 {
00065 ROS_INFO("Constructor joint trajectory downloader node");
00066
00067 this->sub_joint_trajectory_ = this->node_.subscribe("command",
00068 0, &JointTrajectoryDownloader::jointTrajectoryCB, this);
00069 this->robot_ = robotConnecton;
00070 this->robot_->makeConnect();
00071 ROS_INFO("Joint trajectory downloader node initialized");
00072 }
00073
00074 JointTrajectoryDownloader::~JointTrajectoryDownloader()
00075 {
00076 trajectoryStop();
00077 this->sub_joint_trajectory_.shutdown();
00078 }
00079
00080 void JointTrajectoryDownloader::jointTrajectoryCB(
00081 const trajectory_msgs::JointTrajectoryConstPtr &msg)
00082 {
00083 ROS_INFO("Receiving joint trajectory message");
00084
00085 if (!checkTrajectory(msg))
00086 {
00087 ROS_ERROR("Joint trajectory check failed, trajectory not downloaded");
00088 return;
00089 }
00090
00091 std::vector<double> joint_velocity_limits;
00092
00093 if (!getVelocityLimits("robot_description", msg, joint_velocity_limits))
00094 {
00095 ROS_ERROR("Failed to get joint velocity limits");
00096 return;
00097 }
00098
00099 #ifdef SEND_TRAJ_TO_ROBOT
00100
00101 if (!this->robot_->isConnected())
00102 {
00103 ROS_WARN("Attempting robot reconnection");
00104 this->robot_->makeConnect();
00105 }
00106 #endif
00107
00108 #ifdef GENERATE_LOCAL_JOB_FILE
00109
00110 JointTraj traj;
00111 TrajectoryJob job;
00112 job.init("jtd.job");
00113
00114 #endif
00115
00116 ROS_INFO("Sending trajectory points, size: %d", msg->points.size());
00117
00118 for (int i = 0; i < msg->points.size(); i++)
00119 {
00120 ROS_INFO("Sending joints trajectory point[%d]", i);
00121
00122 JointTrajPt jPt;
00123 JointTrajPtMessage jMsg;
00124 SimpleMessage topic;
00125
00126
00127
00128
00129 ROS_INFO("Performing joint velocities copy");
00130 std::vector<double> joint_velocities(0.0);
00131 double velocity =0 ;
00132 joint_velocities.resize(msg->joint_names.size(), 0.0);
00133 for (int j = 0; j < joint_velocities.size(); j++)
00134 {
00135 joint_velocities[j] = msg->points[i].velocities[j];
00136 }
00137 ROS_INFO("Joint velocities copied");
00138 velocity = toMotomanVelocity(joint_velocity_limits, joint_velocities);
00139
00140 jPt.setVelocity(velocity);
00141
00142
00143
00144 if (0 == i)
00145 {
00146 ROS_INFO("First trajectory point, setting special sequence value");
00147 jPt.setSequence(SpecialSeqValues::START_TRAJECTORY_DOWNLOAD);
00148 }
00149 else if (msg->points.size() - 1 == i)
00150 {
00151 ROS_INFO("Last trajectory point, setting special sequence value");
00152 jPt.setSequence(SpecialSeqValues::END_TRAJECTORY);
00153 }
00154 else
00155 {
00156 jPt.setSequence(i);
00157 }
00158
00159
00160 JointData data;
00161 for (int j = 0; j < msg->joint_names.size(); j++)
00162 {
00163 data.setJoint(j, msg->points[i].positions[j]);
00164 }
00165
00166
00167 jPt.setJointPosition(data);
00168
00169 jMsg.init(jPt);
00170 jMsg.toTopic(topic);
00171
00172 #ifdef SEND_TRAJ_TO_ROBOT
00173 ROS_INFO("Sending joint trajectory point");
00174 if (this->robot_->sendMsg(topic))
00175 {
00176 ROS_INFO("Point[%d] sent to controller", i);
00177 }
00178 else
00179 {
00180 ROS_WARN("Failed sent joint point, skipping point");
00181 }
00182 #endif
00183
00184 #ifdef GENERATE_LOCAL_JOB_FILE
00185
00186 ROS_INFO("Adding joint point to local trajectory");
00187 traj.addPoint(jPt);
00188
00189 #endif
00190
00191 }
00192
00193 #ifdef GENERATE_LOCAL_JOB_FILE
00194
00195 const int JOB_BUFFER_SIZE = 500000;
00196 char jobBuffer[JOB_BUFFER_SIZE];
00197 job.toJobString(traj, &jobBuffer[0], JOB_BUFFER_SIZE);
00198 std::ofstream file;
00199 file.open(job.getName());
00200 if (file.is_open())
00201 {
00202 ROS_INFO_STREAM("Writing job to file: " << job.getName());
00203 file << jobBuffer;
00204 }
00205 else
00206 {
00207 ROS_WARN_STREAM("Failed to open job file: " << job.getName());
00208 }
00209 file.close();
00210
00211 #endif
00212
00213
00214
00215 }
00216
00217 void JointTrajectoryDownloader::trajectoryStop()
00218 {
00219 JointTrajPtMessage jMsg;
00220 SimpleMessage msg;
00221 SimpleMessage reply;
00222
00223 ROS_INFO("Joint trajectory downloader: entering stopping state");
00224 jMsg.point_.setSequence(SpecialSeqValues::STOP_TRAJECTORY);
00225 jMsg.toRequest(msg);
00226 ROS_DEBUG("Sending stop command");
00227 this->robot_->sendAndReceiveMsg(msg, reply);
00228 ROS_DEBUG("Stop command sent");
00229 }
00230
00231 }
00232 }
00233