joint_feedback_relay_handler.cpp
Go to the documentation of this file.
00001 /*
00002 * Software License Agreement (BSD License)
00003 *
00004 * Copyright (c) 2013, 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 "motoman_driver/industrial_robot_client/joint_feedback_relay_handler.h"
00033 #include "simple_message/log_wrapper.h"
00034 #include <map>
00035 #include <string>
00036 #include <vector>
00037 
00038 using industrial::joint_data::JointData;
00039 using industrial::shared_types::shared_real;
00040 namespace StandardMsgTypes = industrial::simple_message::StandardMsgTypes;
00041 
00042 namespace industrial_robot_client
00043 {
00044 namespace joint_feedback_relay_handler
00045 {
00046 
00047 bool JointFeedbackRelayHandler::init(SmplMsgConnection* connection,
00048                                      std::map<int, RobotGroup> &robot_groups)
00049 {
00050   this->version_0_ = false;
00051   bool rtn = JointRelayHandler::init(connection, static_cast<int>(StandardMsgTypes::JOINT_FEEDBACK), robot_groups);
00052   // try to read robot_id parameter, if none specified
00053   if ((robot_id_ < 0))
00054     node_.param("robot_id", robot_id_, 0);
00055   return rtn;
00056 }
00057 
00058 bool JointFeedbackRelayHandler::init(SmplMsgConnection* connection,
00059                                      std::vector<std::string> &joint_names)
00060 {
00061   this->version_0_ = true;
00062   bool rtn = JointRelayHandler::init(connection, static_cast<int>(StandardMsgTypes::JOINT_FEEDBACK), joint_names);
00063 
00064   // try to read robot_id parameter, if none specified
00065   if ((robot_id_ < 0))
00066     node_.param("robot_id", robot_id_, 0);
00067 
00068   return rtn;
00069 }
00070 
00071 
00072 bool JointFeedbackRelayHandler::create_messages(SimpleMessage& msg_in,
00073     control_msgs::FollowJointTrajectoryFeedback* control_state,
00074     sensor_msgs::JointState* sensor_state)
00075 {
00076   // inspect robot_id field first, to avoid "Failed to Convert" message
00077   JointFeedbackMessage tmp_msg;
00078 
00079   tmp_msg.init(msg_in);
00080 
00081   if (this->version_0_)
00082     return JointRelayHandler::create_messages(msg_in, control_state, sensor_state);
00083   else
00084     return JointFeedbackRelayHandler::create_messages(msg_in, control_state, sensor_state, tmp_msg.getRobotID());
00085 }
00086 
00087 bool JointFeedbackRelayHandler::create_messages(SimpleMessage& msg_in,
00088     control_msgs::FollowJointTrajectoryFeedback* control_state,
00089     sensor_msgs::JointState* sensor_state, int robot_id)
00090 {
00091   DynamicJointsGroup all_joint_state;
00092   if (!convert_message(msg_in, &all_joint_state, robot_id))
00093   {
00094     LOG_ERROR("Failed to convert SimpleMessage");
00095     return false;
00096   }
00097   // apply transform, if required
00098   DynamicJointsGroup xform_joint_state;
00099   if (!transform(all_joint_state, &xform_joint_state))
00100   {
00101     LOG_ERROR("Failed to transform joint state");
00102     return false;
00103   }
00104 
00105   // select specific joints for publishing
00106   DynamicJointsGroup pub_joint_state;
00107   std::vector<std::string> pub_joint_names;
00108   if (!select(xform_joint_state, robot_groups_[robot_id].get_joint_names(), &pub_joint_state, &pub_joint_names))
00109   {
00110     LOG_ERROR("Failed to select joints for publishing");
00111     return false;
00112   }
00113   // assign values to messages
00114   *control_state = control_msgs::FollowJointTrajectoryFeedback();  // always start with a "clean" message
00115   control_state->header.stamp = ros::Time::now();
00116   control_state->joint_names = pub_joint_names;
00117   control_state->actual.positions = pub_joint_state.positions;
00118   control_state->actual.velocities = pub_joint_state.velocities;
00119   control_state->actual.accelerations = pub_joint_state.accelerations;
00120   control_state->actual.time_from_start = pub_joint_state.time_from_start;
00121 
00122   *sensor_state = sensor_msgs::JointState();  // always start with a "clean" message
00123   sensor_state->header.stamp = ros::Time::now();
00124   sensor_state->name = pub_joint_names;
00125   sensor_state->position = pub_joint_state.positions;
00126   sensor_state->velocity = pub_joint_state.velocities;
00127 
00128   this->pub_controls_[robot_id].publish(*control_state);
00129   this->pub_states_[robot_id].publish(*sensor_state);
00130 
00131   return true;
00132 }
00133 
00134 bool JointFeedbackRelayHandler::convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
00135 {
00136   JointFeedbackMessage joint_feedback_msg;
00137   if (!joint_feedback_msg.init(msg_in))
00138   {
00139     LOG_ERROR("Failed to initialize joint feedback message");
00140     return false;
00141   }
00142 
00143   return convert_message(joint_feedback_msg, joint_state, robot_id);
00144 }
00145 
00146 bool JointFeedbackRelayHandler::convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state)
00147 {
00148   JointFeedbackMessage joint_feedback_msg;
00149   if (!joint_feedback_msg.init(msg_in))
00150   {
00151     LOG_ERROR("Failed to initialize joint feedback message");
00152     return false;
00153   }
00154 
00155   return convert_message(joint_feedback_msg, joint_state);
00156 }
00157 
00158 bool JointFeedbackRelayHandler::JointDataToVector(const JointData &joints,
00159     std::vector<double> &vec,
00160     int len)
00161 {
00162   if ((len < 0) || (len > joints.getMaxNumJoints()))
00163   {
00164     LOG_ERROR("Failed to copy JointData.  Len (%d) out of range (0 to %d)",
00165               len, joints.getMaxNumJoints());
00166     return false;
00167   }
00168 
00169   vec.resize(len);
00170   for (int i = 0; i < len; ++i)
00171     vec[i] = joints.getJoint(i);
00172 
00173   return true;
00174 }
00175 
00176 bool JointFeedbackRelayHandler::convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
00177 {
00178   JointData values;
00179   int num_jnts = robot_groups_[robot_id].get_joint_names().size();
00180   // copy position data
00181   if (msg_in.getPositions(values))
00182   {
00183     if (!JointDataToVector(values, joint_state->positions, num_jnts))
00184     {
00185       LOG_ERROR("Failed to parse position data from JointFeedbackMessage");
00186       return false;
00187     }
00188   }
00189   else
00190     joint_state->positions.clear();
00191 
00192   // copy velocity data
00193   if (msg_in.getVelocities(values))
00194   {
00195     if (!JointDataToVector(values, joint_state->velocities, num_jnts))
00196     {
00197       LOG_ERROR("Failed to parse velocity data from JointFeedbackMessage");
00198       return false;
00199     }
00200   }
00201   else
00202     joint_state->velocities.clear();
00203 
00204   // copy acceleration data
00205   if (msg_in.getAccelerations(values))
00206   {
00207     if (!JointDataToVector(values, joint_state->accelerations, num_jnts))
00208     {
00209       LOG_ERROR("Failed to parse acceleration data from JointFeedbackMessage");
00210       return false;
00211     }
00212   }
00213   else
00214     joint_state->accelerations.clear();
00215 
00216   // copy timestamp data
00217   shared_real value;
00218   if (msg_in.getTime(value))
00219     joint_state->time_from_start = ros::Duration(value);
00220   else
00221     joint_state->time_from_start = ros::Duration(0);
00222 
00223   return true;
00224 }
00225 
00226 bool JointFeedbackRelayHandler::convert_message(JointFeedbackMessage& msg_in, JointTrajectoryPoint* joint_state)
00227 {
00228   JointData values;
00229   int num_jnts = all_joint_names_.size();
00230 
00231   // copy position data
00232   if (msg_in.getPositions(values))
00233   {
00234     if (!JointDataToVector(values, joint_state->positions, num_jnts))
00235     {
00236       LOG_ERROR("Failed to parse position data from JointFeedbackMessage");
00237       return false;
00238     }
00239   }
00240   else
00241     joint_state->positions.clear();
00242 
00243   // copy velocity data
00244   if (msg_in.getVelocities(values))
00245   {
00246     if (!JointDataToVector(values, joint_state->velocities, num_jnts))
00247     {
00248       LOG_ERROR("Failed to parse velocity data from JointFeedbackMessage");
00249       return false;
00250     }
00251   }
00252   else
00253     joint_state->velocities.clear();
00254 
00255   // copy acceleration data
00256   if (msg_in.getAccelerations(values))
00257   {
00258     if (!JointDataToVector(values, joint_state->accelerations, num_jnts))
00259     {
00260       LOG_ERROR("Failed to parse acceleration data from JointFeedbackMessage");
00261       return false;
00262     }
00263   }
00264   else
00265     joint_state->accelerations.clear();
00266 
00267   // copy timestamp data
00268   shared_real value;
00269   if (msg_in.getTime(value))
00270     joint_state->time_from_start = ros::Duration(value);
00271   else
00272     joint_state->time_from_start = ros::Duration(0);
00273 
00274   return true;
00275 }
00276 
00277 bool JointFeedbackRelayHandler::select(const DynamicJointsGroup& all_joint_state, const std::vector<std::string>& all_joint_names,
00278                                        DynamicJointsGroup* pub_joint_state, std::vector<std::string>* pub_joint_names)
00279 {
00280 
00281   ROS_ASSERT(all_joint_state.positions.size() == all_joint_names.size());
00282 
00283   *pub_joint_state = DynamicJointsGroup();  // start with a "clean" message
00284   pub_joint_names->clear();
00285 
00286   // skip over "blank" joint names
00287   for (int i = 0; i < all_joint_names.size(); ++i)
00288   {
00289     if (all_joint_names[i].empty())
00290       continue;
00291     pub_joint_names->push_back(all_joint_names[i]);
00292     if (!all_joint_state.positions.empty())
00293       pub_joint_state->positions.push_back(all_joint_state.positions[i]);
00294     if (!all_joint_state.velocities.empty())
00295       pub_joint_state->velocities.push_back(all_joint_state.velocities[i]);
00296     if (!all_joint_state.accelerations.empty())
00297       pub_joint_state->accelerations.push_back(all_joint_state.accelerations[i]);
00298   }
00299   pub_joint_state->time_from_start = all_joint_state.time_from_start;
00300 
00301   return true;
00302 }
00303 
00304 }  // namespace joint_feedback_relay_handler
00305 }  // namespace industrial_robot_client
00306 
00307 
00308 
00309 


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