joint_feedback_ex_relay_handler.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2014, Fraunhofer IPA
00005  * Author: Thiago de Freitas
00006  *
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  *  * Redistributions of source code must retain the above copyright
00013  *  notice, this list of conditions and the following disclaimer.
00014  *  * Redistributions in binary form must reproduce the above copyright
00015  *  notice, this list of conditions and the following disclaimer in the
00016  *  documentation and/or other materials provided with the distribution.
00017  *  * Neither the name of the Southwest Research Institute, nor the names
00018  *  of its contributors may be used to endorse or promote products derived
00019  *  from this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  */
00033 
00034 #include <vector>
00035 #include <map>
00036 #include <algorithm>
00037 #include <string>
00038 #include "motoman_driver/industrial_robot_client/joint_feedback_ex_relay_handler.h"
00039 #include "simple_message/log_wrapper.h"
00040 #include "motoman_driver/simple_message/motoman_simple_message.h"
00041 
00042 using industrial::joint_data::JointData;
00043 using industrial::shared_types::shared_real;
00044 namespace MotomanMsgTypes = motoman::simple_message::MotomanMsgTypes;
00045 namespace ValidFieldTypes = industrial::joint_feedback::ValidFieldTypes;
00046 
00047 namespace industrial_robot_client
00048 {
00049 namespace joint_feedback_ex_relay_handler
00050 {
00051 bool JointFeedbackExRelayHandler::init(SmplMsgConnection* connection,
00052                                        std::map<int, RobotGroup> &robot_groups)
00053 {
00054   ROS_INFO_STREAM("Creating joint_feedback_ex_relay_handler with " << robot_groups.size() << " groups");
00055   this->pub_joint_control_state_ =
00056     this->node_.advertise<control_msgs::FollowJointTrajectoryFeedback>("feedback_states", 1);
00057   this->dynamic_pub_joint_control_state_ =
00058     this->node_.advertise<motoman_msgs::DynamicJointTrajectoryFeedback>("dynamic_feedback_states", 1);
00059 
00060   this->pub_joint_sensor_state_ = this->node_.advertise<sensor_msgs::JointState>("joint_states", 1);
00061 
00062   this->robot_groups_ = robot_groups;
00063   this->version_0_ = false;
00064   bool rtn = JointRelayHandler::init(connection, static_cast<int>(MotomanMsgTypes::ROS_MSG_MOTO_JOINT_FEEDBACK_EX), robot_groups);
00065   // try to read groups_number parameter, if none specified
00066   if ((groups_number_ < 0))
00067     node_.param("groups_number", groups_number_, 0);
00068   return rtn;
00069 }
00070 
00071 bool JointFeedbackExRelayHandler::init(SmplMsgConnection* connection,
00072                                        std::vector<std::string> &joint_names)
00073 {
00074   this->version_0_ = true;
00075   bool rtn = JointRelayHandler::init(connection, static_cast<int>(MotomanMsgTypes::ROS_MSG_MOTO_JOINT_FEEDBACK_EX), joint_names);
00076   // try to read groups_number parameter, if none specified
00077   if ((groups_number_ < 0))
00078     node_.param("groups_number", groups_number_, 0);
00079   return rtn;
00080 }
00081 
00082 
00083 bool JointFeedbackExRelayHandler::create_messages(SimpleMessage& msg_in,
00084     control_msgs::FollowJointTrajectoryFeedback* control_state,
00085     sensor_msgs::JointState* sensor_state)
00086 {
00087   // inspect groups_number field first, to avoid "Failed to Convert" message
00088   JointFeedbackExMessage tmp_msg;
00089   tmp_msg.init(msg_in);
00090   motoman_msgs::DynamicJointTrajectoryFeedback dynamic_control_state;
00091 
00092   for (int i = 0; i < tmp_msg.getJointMessages().size(); i++)
00093   {
00094     int group_number = tmp_msg.getJointMessages()[i].getRobotID();
00095 
00096     create_messages(tmp_msg.getJointMessages()[i], control_state, sensor_state, group_number);
00097     motoman_msgs::DynamicJointState dyn_joint_state;
00098     dyn_joint_state.num_joints = control_state->joint_names.size();
00099     dyn_joint_state.group_number = group_number;
00100     dyn_joint_state.valid_fields = this->valid_fields_from_message_;
00101     dyn_joint_state.positions = control_state->actual.positions;
00102     dyn_joint_state.velocities = control_state->actual.velocities;
00103     dyn_joint_state.accelerations = control_state->actual.accelerations;
00104     dynamic_control_state.joint_feedbacks.push_back(dyn_joint_state);
00105   }
00106   dynamic_control_state.header.stamp = ros::Time::now();
00107   dynamic_control_state.num_groups = tmp_msg.getGroupsNumber();
00108   this->dynamic_pub_joint_control_state_.publish(dynamic_control_state);
00109 }
00110 
00111 bool JointFeedbackExRelayHandler::create_messages(JointFeedbackMessage& msg_in,
00112     control_msgs::FollowJointTrajectoryFeedback* control_state,
00113     sensor_msgs::JointState* sensor_state, int robot_id)
00114 {
00115   DynamicJointsGroup all_joint_state;
00116   if (!JointFeedbackExRelayHandler::convert_message(msg_in, &all_joint_state, robot_id))
00117   {
00118     LOG_ERROR("Failed to convert SimpleMessage");
00119     return false;
00120   }
00121   // apply transform, if required
00122   DynamicJointsGroup xform_joint_state;
00123   if (!transform(all_joint_state, &xform_joint_state))
00124   {
00125     LOG_ERROR("Failed to transform joint state");
00126     return false;
00127   }
00128 
00129   // select specific joints for publishing
00130   DynamicJointsGroup pub_joint_state;
00131   std::vector<std::string> pub_joint_names;
00132   if (!select(xform_joint_state, robot_groups_[robot_id].get_joint_names(), &pub_joint_state, &pub_joint_names))
00133   {
00134     LOG_ERROR("Failed to select joints for publishing");
00135     return false;
00136   }
00137 
00138 
00139   // assign values to messages
00140   *control_state = control_msgs::FollowJointTrajectoryFeedback();  // always start with a "clean" message
00141   control_state->header.stamp = ros::Time::now();
00142   control_state->joint_names = pub_joint_names;
00143   control_state->actual.positions = pub_joint_state.positions;
00144   control_state->actual.velocities = pub_joint_state.velocities;
00145   control_state->actual.accelerations = pub_joint_state.accelerations;
00146   control_state->actual.time_from_start = pub_joint_state.time_from_start;
00147 
00148   this->pub_joint_control_state_.publish(*control_state);
00149 
00150   *sensor_state = sensor_msgs::JointState();  // always start with a "clean" message
00151   sensor_state->header.stamp = ros::Time::now();
00152   sensor_state->name = pub_joint_names;
00153   sensor_state->position = pub_joint_state.positions;
00154   sensor_state->velocity = pub_joint_state.velocities;
00155 
00156   this->pub_joint_sensor_state_.publish(*sensor_state);
00157 
00158   return true;
00159 }
00160 
00161 
00162 bool JointFeedbackExRelayHandler::convert_message(JointFeedbackMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
00163 {
00164   JointData values;
00165 
00166   int num_jnts = robot_groups_[robot_id].get_joint_names().size();
00167 
00168   // copy position data
00169   bool position_field = msg_in.getPositions(values);
00170   if (position_field)
00171   {
00172     this->valid_fields_from_message_ |= ValidFieldTypes::POSITION;
00173     if (!JointDataToVector(values, joint_state->positions, num_jnts))
00174     {
00175       LOG_ERROR("Failed to parse position data from JointFeedbackMessage");
00176       return false;
00177     }
00178   }
00179   else
00180   {
00181     joint_state->positions.clear();
00182     this->valid_fields_from_message_ &= ~ValidFieldTypes::POSITION;
00183   }
00184 
00185   // copy velocity data
00186   bool velocity_field = msg_in.getVelocities(values);
00187   if (velocity_field)
00188   {
00189     this->valid_fields_from_message_ |= ValidFieldTypes::VELOCITY;
00190     if (!JointDataToVector(values, joint_state->velocities, num_jnts))
00191     {
00192       LOG_ERROR("Failed to parse velocity data from JointFeedbackMessage");
00193       return false;
00194     }
00195   }
00196   else
00197   {
00198     joint_state->velocities.clear();
00199     this->valid_fields_from_message_ &= ~ValidFieldTypes::VELOCITY;
00200   }
00201 
00202   // copy acceleration data
00203   bool acceleration_field = msg_in.getAccelerations(values);
00204   if (acceleration_field)
00205   {
00206     this->valid_fields_from_message_ |= ValidFieldTypes::ACCELERATION;
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   {
00215     joint_state->accelerations.clear();
00216     this->valid_fields_from_message_ &= ~ValidFieldTypes::ACCELERATION;
00217   }
00218 
00219   // copy timestamp data
00220   shared_real value;
00221   bool time_field = msg_in.getTime(value);
00222   if (time_field)
00223   {
00224     this->valid_fields_from_message_ |= ValidFieldTypes::TIME;
00225     joint_state->time_from_start = ros::Duration(value);
00226   }
00227   else
00228   {
00229     joint_state->time_from_start = ros::Duration(0);
00230     this->valid_fields_from_message_ &= ~ValidFieldTypes::TIME;
00231   }
00232 
00233   return true;
00234 }
00235 
00236 bool JointFeedbackExRelayHandler::JointDataToVector(const JointData &joints,
00237     std::vector<double> &vec,
00238     int len)
00239 {
00240   if ((len < 0) || (len > joints.getMaxNumJoints()))
00241   {
00242     LOG_ERROR("Failed to copy JointData.  Len (%d) out of range (0 to %d)",
00243               len, joints.getMaxNumJoints());
00244     return false;
00245   }
00246 
00247   vec.resize(len);
00248   for (int i = 0; i < len; ++i)
00249     vec[i] = joints.getJoint(i);
00250 
00251   return true;
00252 }
00253 
00254 
00255 }  // namespace joint_feedback_ex_relay_handler
00256 }  // namespace industrial_robot_client


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