joint_relay_handler.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 <algorithm>
00033 #include <map>
00034 #include <vector>
00035 #include <string>
00036 
00037 #include "motoman_driver/industrial_robot_client/joint_relay_handler.h"
00038 #include "simple_message/log_wrapper.h"
00039 
00040 using industrial::message_handler::MessageHandler;
00041 using industrial::shared_types::shared_real;
00042 using industrial::smpl_msg_connection::SmplMsgConnection;
00043 namespace CommTypes = industrial::simple_message::CommTypes;
00044 namespace ReplyTypes = industrial::simple_message::ReplyTypes;
00045 
00046 namespace industrial_robot_client
00047 {
00048 namespace joint_relay_handler
00049 {
00050 
00051 bool JointRelayHandler::init(SmplMsgConnection* connection, int msg_type, std::map<int, RobotGroup> &robot_groups)
00052 {
00053   this->robot_groups_ = robot_groups;
00054   for (it_type iterator = robot_groups.begin(); iterator != robot_groups.end(); iterator++)
00055   {
00056     std::string name_str, ns_str;
00057     int robot_id = iterator->first;
00058     name_str = iterator->second.get_name();
00059     ns_str = iterator->second.get_ns();
00060 
00061     this->pub_joint_control_state_ =
00062       this->node_.advertise<control_msgs::FollowJointTrajectoryFeedback>(ns_str + "/" + name_str + "/feedback_states", 1);
00063 
00064     this->pub_joint_sensor_state_ = this->node_.advertise<sensor_msgs::JointState>(ns_str + "/" + name_str + "/joint_states", 1);
00065 
00066     this->pub_controls_[robot_id] = this->pub_joint_control_state_;
00067     this->pub_states_[robot_id] = this->pub_joint_sensor_state_;
00068   }
00069 
00070 
00071 
00072 
00073   return MessageHandler::init(msg_type, connection);
00074 }
00075 
00076 bool JointRelayHandler::init(SmplMsgConnection* connection, int msg_type, std::vector<std::string>& joint_names)
00077 {
00078   this->pub_joint_control_state_ =
00079     this->node_.advertise<control_msgs::FollowJointTrajectoryFeedback>("feedback_states", 1);
00080 
00081   this->pub_joint_sensor_state_ = this->node_.advertise<sensor_msgs::JointState>("joint_states", 1);
00082 
00083   // save "complete" joint-name list, preserving any blank entries for later use
00084   this->all_joint_names_ = joint_names;
00085 
00086   return MessageHandler::init(msg_type, connection);
00087 }
00088 
00091 bool JointRelayHandler::internalCB(SimpleMessage& msg_in)
00092 {
00093   control_msgs::FollowJointTrajectoryFeedback control_state;
00094   sensor_msgs::JointState sensor_state;
00095   bool rtn = true;
00096 
00097   if (create_messages(msg_in, &control_state, &sensor_state))
00098   {
00099     rtn = true;
00100   }
00101   else
00102     rtn = false;
00103 
00104   // Reply back to the controller if the sender requested it.
00105   if (CommTypes::SERVICE_REQUEST == msg_in.getMessageType())
00106   {
00107     SimpleMessage reply;
00108     reply.init(msg_in.getMessageType(),
00109                CommTypes::SERVICE_REPLY,
00110                rtn ? ReplyTypes::SUCCESS : ReplyTypes::FAILURE);
00111     this->getConnection()->sendMsg(reply);
00112   }
00113 
00114   return rtn;
00115 }
00116 
00117 // TODO: Add support for other message fields (effort, desired pos)
00118 bool JointRelayHandler::create_messages(SimpleMessage& msg_in,
00119                                         control_msgs::FollowJointTrajectoryFeedback* control_state,
00120                                         sensor_msgs::JointState* sensor_state)
00121 {
00122   // read state from robot message
00123   JointTrajectoryPoint all_joint_state;
00124   if (!convert_message(msg_in, &all_joint_state))
00125   {
00126     LOG_ERROR("Failed to convert SimpleMessage");
00127     return false;
00128   }
00129   // apply transform, if required
00130   JointTrajectoryPoint xform_joint_state;
00131   if (!transform(all_joint_state, &xform_joint_state))
00132   {
00133     LOG_ERROR("Failed to transform joint state");
00134     return false;
00135   }
00136 
00137   // select specific joints for publishing
00138   JointTrajectoryPoint pub_joint_state;
00139   std::vector<std::string> pub_joint_names;
00140   if (!select(xform_joint_state, all_joint_names_, &pub_joint_state, &pub_joint_names))
00141   {
00142     LOG_ERROR("Failed to select joints for publishing");
00143     return false;
00144   }
00145 
00146   // assign values to messages
00147   *control_state = control_msgs::FollowJointTrajectoryFeedback();  // always start with a "clean" message
00148   control_state->header.stamp = ros::Time::now();
00149   control_state->joint_names = pub_joint_names;
00150   control_state->actual.positions = pub_joint_state.positions;
00151   control_state->actual.velocities = pub_joint_state.velocities;
00152   control_state->actual.accelerations = pub_joint_state.accelerations;
00153   control_state->actual.time_from_start = pub_joint_state.time_from_start;
00154 
00155   *sensor_state = sensor_msgs::JointState();  // always start with a "clean" message
00156   sensor_state->header.stamp = ros::Time::now();
00157   sensor_state->name = pub_joint_names;
00158   sensor_state->position = pub_joint_state.positions;
00159   sensor_state->velocity = pub_joint_state.velocities;
00160 
00161   this->pub_joint_control_state_.publish(*control_state);
00162   this->pub_joint_sensor_state_.publish(*sensor_state);
00163 
00164   return true;
00165 }
00166 
00167 // TODO: Add support for other message fields (effort, desired pos)
00168 bool JointRelayHandler::create_messages(SimpleMessage& msg_in,
00169                                         control_msgs::FollowJointTrajectoryFeedback* control_state,
00170                                         sensor_msgs::JointState* sensor_state, int robot_id)
00171 {
00172   DynamicJointsGroup all_joint_state;
00173   if (!convert_message(msg_in, &all_joint_state, robot_id))
00174   {
00175     LOG_ERROR("Failed to convert SimpleMessage");
00176     return false;
00177   }
00178   // apply transform, if required
00179   DynamicJointsGroup xform_joint_state;
00180   if (!transform(all_joint_state, &xform_joint_state))
00181   {
00182     LOG_ERROR("Failed to transform joint state");
00183     return false;
00184   }
00185 
00186   // select specific joints for publishing
00187   DynamicJointsGroup pub_joint_state;
00188   std::vector<std::string> pub_joint_names;
00189   if (!select(xform_joint_state, robot_groups_[robot_id].get_joint_names(), &pub_joint_state, &pub_joint_names))
00190   {
00191     LOG_ERROR("Failed to select joints for publishing");
00192     return false;
00193   }
00194   // assign values to messages
00195   *control_state = control_msgs::FollowJointTrajectoryFeedback();  // always start with a "clean" message
00196   control_state->header.stamp = ros::Time::now();
00197   control_state->joint_names = pub_joint_names;
00198   control_state->actual.positions = pub_joint_state.positions;
00199   control_state->actual.velocities = pub_joint_state.velocities;
00200   control_state->actual.accelerations = pub_joint_state.accelerations;
00201   control_state->actual.time_from_start = pub_joint_state.time_from_start;
00202 
00203   *sensor_state = sensor_msgs::JointState();  // always start with a "clean" message
00204   sensor_state->header.stamp = ros::Time::now();
00205   sensor_state->name = pub_joint_names;
00206   sensor_state->position = pub_joint_state.positions;
00207   sensor_state->velocity = pub_joint_state.velocities;
00208 
00209   this->pub_controls_[robot_id].publish(*control_state);
00210   this->pub_states_[robot_id].publish(*sensor_state);
00211 
00212   return true;
00213 }
00214 
00215 bool JointRelayHandler::convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state)
00216 {
00217   JointMessage joint_msg;
00218 
00219   if (!joint_msg.init(msg_in))
00220   {
00221     LOG_ERROR("Failed to initialize joint message");
00222     return false;
00223   }
00224 
00225   return convert_message(joint_msg, joint_state);
00226 }
00227 
00228 bool JointRelayHandler::convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
00229 {
00230   JointMessage joint_msg;
00231 
00232   if (!joint_msg.init(msg_in))
00233   {
00234     LOG_ERROR("Failed to initialize joint message");
00235     return false;
00236   }
00237 
00238   return convert_message(joint_msg, joint_state, robot_id);
00239 }
00240 
00241 bool JointRelayHandler::convert_message(JointMessage& msg_in, JointTrajectoryPoint* joint_state)
00242 {
00243   // copy position data
00244   int num_jnts = all_joint_names_.size();
00245   joint_state->positions.resize(num_jnts);
00246   for (int i = 0; i < num_jnts; ++i)
00247   {
00248     shared_real value;
00249     if (msg_in.getJoints().getJoint(i, value))
00250     {
00251       joint_state->positions[i] = value;
00252     }
00253     else
00254       LOG_ERROR("Failed to parse position #%d from JointMessage", i);
00255   }
00256 
00257   // these fields are not provided by JointMessage
00258   joint_state->velocities.clear();
00259   joint_state->accelerations.clear();
00260   joint_state->time_from_start = ros::Duration(0);
00261 
00262   return true;
00263 }
00264 
00265 bool JointRelayHandler::convert_message(JointMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
00266 {
00267   // copy position data
00268   int num_jnts = robot_groups_[robot_id].get_joint_names().size();
00269   joint_state->positions.resize(num_jnts);
00270   for (int i = 0; i < num_jnts; ++i)
00271   {
00272     shared_real value;
00273     if (msg_in.getJoints().getJoint(i, value))
00274     {
00275       joint_state->positions[i] = value;
00276     }
00277     else
00278       LOG_ERROR("Failed to convert message");
00279   }
00280 
00281   // these fields are not provided by JointMessage
00282   joint_state->velocities.clear();
00283   joint_state->accelerations.clear();
00284   joint_state->time_from_start = ros::Duration(0);
00285 
00286   return true;
00287 }
00288 
00289 bool JointRelayHandler::select(const JointTrajectoryPoint& all_joint_state, const std::vector<std::string>& all_joint_names,
00290                                JointTrajectoryPoint* pub_joint_state, std::vector<std::string>* pub_joint_names)
00291 {
00292   ROS_ASSERT(all_joint_state.positions.size() == all_joint_names.size());
00293 
00294   *pub_joint_state = JointTrajectoryPoint();  // start with a "clean" message
00295   pub_joint_names->clear();
00296 
00297   // skip over "blank" joint names
00298   for (int i = 0; i < all_joint_names.size(); ++i)
00299   {
00300     if (all_joint_names[i].empty())
00301       continue;
00302 
00303     pub_joint_names->push_back(all_joint_names[i]);
00304     if (!all_joint_state.positions.empty())
00305       pub_joint_state->positions.push_back(all_joint_state.positions[i]);
00306     if (!all_joint_state.velocities.empty())
00307       pub_joint_state->velocities.push_back(all_joint_state.velocities[i]);
00308     if (!all_joint_state.accelerations.empty())
00309       pub_joint_state->accelerations.push_back(all_joint_state.accelerations[i]);
00310   }
00311   pub_joint_state->time_from_start = all_joint_state.time_from_start;
00312 
00313   return true;
00314 }
00315 
00316 bool JointRelayHandler::select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
00317                                DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names)
00318 {
00319 
00320   ROS_ASSERT(all_joint_state.positions.size() == all_joint_names.size());
00321 
00322   *pub_joint_state = DynamicJointsGroup();  // start with a "clean" message
00323   pub_joint_names->clear();
00324 
00325   // skip over "blank" joint names
00326   for (int i = 0; i < all_joint_names.size(); ++i)
00327   {
00328     if (all_joint_names[i].empty())
00329       continue;
00330     pub_joint_names->push_back(all_joint_names[i]);
00331     if (!all_joint_state.positions.empty())
00332       pub_joint_state->positions.push_back(all_joint_state.positions[i]);
00333     if (!all_joint_state.velocities.empty())
00334       pub_joint_state->velocities.push_back(all_joint_state.velocities[i]);
00335     if (!all_joint_state.accelerations.empty())
00336       pub_joint_state->accelerations.push_back(all_joint_state.accelerations[i]);
00337   }
00338   pub_joint_state->time_from_start = all_joint_state.time_from_start;
00339 
00340   return true;
00341 }
00342 
00343 }  // namespace joint_relay_handler
00344 }  // namespace industrial_robot_client
00345 
00346 
00347 
00348 


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:57