joint_relay_handler.cpp
Go to the documentation of this file.
1 /*
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Southwest Research Institute
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions are met:
9 *
10 * * Redistributions of source code must retain the above copyright
11 * notice, this list of conditions and the following disclaimer.
12 * * Redistributions in binary form must reproduce the above copyright
13 * notice, this list of conditions and the following disclaimer in the
14 * documentation and/or other materials provided with the distribution.
15 * * Neither the name of the Southwest Research Institute, nor the names
16 * of its contributors may be used to endorse or promote products derived
17 * from this software without specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 */
31 
32 #include <algorithm>
33 #include <map>
34 #include <vector>
35 #include <string>
36 
39 
45 
47 {
48 namespace joint_relay_handler
49 {
50 
51 bool JointRelayHandler::init(SmplMsgConnection* connection, int msg_type, std::map<int, RobotGroup> &robot_groups)
52 {
53  this->robot_groups_ = robot_groups;
54  for (it_type iterator = robot_groups.begin(); iterator != robot_groups.end(); iterator++)
55  {
56  std::string name_str, ns_str;
57  int robot_id = iterator->first;
58  name_str = iterator->second.get_name();
59  ns_str = iterator->second.get_ns();
60 
61  this->pub_joint_control_state_ = this->node_.advertise<control_msgs::FollowJointTrajectoryFeedback>(
62  ns_str + "/" + name_str + "/feedback_states", 1);
63 
65  this->node_.advertise<sensor_msgs::JointState>(ns_str + "/" + name_str + "/joint_states", 1);
66 
67  this->pub_controls_[robot_id] = this->pub_joint_control_state_;
68  this->pub_states_[robot_id] = this->pub_joint_sensor_state_;
69  }
70 
71 
72 
73 
74  return MessageHandler::init(msg_type, connection);
75 }
76 
77 bool JointRelayHandler::init(SmplMsgConnection* connection, int msg_type, std::vector<std::string>& joint_names)
78 {
80  this->node_.advertise<control_msgs::FollowJointTrajectoryFeedback>("feedback_states", 1);
81 
82  this->pub_joint_sensor_state_ = this->node_.advertise<sensor_msgs::JointState>("joint_states", 1);
83 
84  // save "complete" joint-name list, preserving any blank entries for later use
85  this->all_joint_names_ = joint_names;
86 
87  return MessageHandler::init(msg_type, connection);
88 }
89 
92 bool JointRelayHandler::internalCB(SimpleMessage& msg_in)
93 {
94  control_msgs::FollowJointTrajectoryFeedback control_state;
95  sensor_msgs::JointState sensor_state;
96  bool rtn = true;
97 
98  if (create_messages(msg_in, &control_state, &sensor_state))
99  {
100  rtn = true;
101  }
102  else
103  rtn = false;
104 
105  // Reply back to the controller if the sender requested it.
106  if (CommTypes::SERVICE_REQUEST == msg_in.getMessageType())
107  {
108  SimpleMessage reply;
109  reply.init(msg_in.getMessageType(),
112  this->getConnection()->sendMsg(reply);
113  }
114 
115  return rtn;
116 }
117 
118 // TODO( ): Add support for other message fields (effort, desired pos)
119 bool JointRelayHandler::create_messages(SimpleMessage& msg_in,
120  control_msgs::FollowJointTrajectoryFeedback* control_state,
121  sensor_msgs::JointState* sensor_state)
122 {
123  // read state from robot message
124  JointTrajectoryPoint all_joint_state;
125  if (!convert_message(msg_in, &all_joint_state))
126  {
127  LOG_ERROR("Failed to convert SimpleMessage");
128  return false;
129  }
130  // apply transform, if required
131  JointTrajectoryPoint xform_joint_state;
132  if (!transform(all_joint_state, &xform_joint_state))
133  {
134  LOG_ERROR("Failed to transform joint state");
135  return false;
136  }
137 
138  // select specific joints for publishing
139  JointTrajectoryPoint pub_joint_state;
140  std::vector<std::string> pub_joint_names;
141  if (!select(xform_joint_state, all_joint_names_, &pub_joint_state, &pub_joint_names))
142  {
143  LOG_ERROR("Failed to select joints for publishing");
144  return false;
145  }
146 
147  // assign values to messages
148  *control_state = control_msgs::FollowJointTrajectoryFeedback(); // always start with a "clean" message
149  control_state->header.stamp = ros::Time::now();
150  control_state->joint_names = pub_joint_names;
151  control_state->actual.positions = pub_joint_state.positions;
152  control_state->actual.velocities = pub_joint_state.velocities;
153  control_state->actual.accelerations = pub_joint_state.accelerations;
154  control_state->actual.time_from_start = pub_joint_state.time_from_start;
155 
156  *sensor_state = sensor_msgs::JointState(); // always start with a "clean" message
157  sensor_state->header.stamp = ros::Time::now();
158  sensor_state->name = pub_joint_names;
159  sensor_state->position = pub_joint_state.positions;
160  sensor_state->velocity = pub_joint_state.velocities;
161 
162  this->pub_joint_control_state_.publish(*control_state);
163  this->pub_joint_sensor_state_.publish(*sensor_state);
164 
165  return true;
166 }
167 
168 // TODO( ): Add support for other message fields (effort, desired pos)
169 bool JointRelayHandler::create_messages(SimpleMessage& msg_in,
170  control_msgs::FollowJointTrajectoryFeedback* control_state,
171  sensor_msgs::JointState* sensor_state, int robot_id)
172 {
173  DynamicJointsGroup all_joint_state;
174  if (!convert_message(msg_in, &all_joint_state, robot_id))
175  {
176  LOG_ERROR("Failed to convert SimpleMessage");
177  return false;
178  }
179  // apply transform, if required
180  DynamicJointsGroup xform_joint_state;
181  if (!transform(all_joint_state, &xform_joint_state))
182  {
183  LOG_ERROR("Failed to transform joint state");
184  return false;
185  }
186 
187  // select specific joints for publishing
188  DynamicJointsGroup pub_joint_state;
189  std::vector<std::string> pub_joint_names;
190  if (!select(xform_joint_state, robot_groups_[robot_id].get_joint_names(), &pub_joint_state, &pub_joint_names))
191  {
192  LOG_ERROR("Failed to select joints for publishing");
193  return false;
194  }
195  // assign values to messages
196  *control_state = control_msgs::FollowJointTrajectoryFeedback(); // always start with a "clean" message
197  control_state->header.stamp = ros::Time::now();
198  control_state->joint_names = pub_joint_names;
199  control_state->actual.positions = pub_joint_state.positions;
200  control_state->actual.velocities = pub_joint_state.velocities;
201  control_state->actual.accelerations = pub_joint_state.accelerations;
202  control_state->actual.time_from_start = pub_joint_state.time_from_start;
203 
204  *sensor_state = sensor_msgs::JointState(); // always start with a "clean" message
205  sensor_state->header.stamp = ros::Time::now();
206  sensor_state->name = pub_joint_names;
207  sensor_state->position = pub_joint_state.positions;
208  sensor_state->velocity = pub_joint_state.velocities;
209 
210  this->pub_controls_[robot_id].publish(*control_state);
211  this->pub_states_[robot_id].publish(*sensor_state);
212 
213  return true;
214 }
215 
216 bool JointRelayHandler::convert_message(SimpleMessage& msg_in, JointTrajectoryPoint* joint_state)
217 {
218  JointMessage joint_msg;
219 
220  if (!joint_msg.init(msg_in))
221  {
222  LOG_ERROR("Failed to initialize joint message");
223  return false;
224  }
225 
226  return convert_message(joint_msg, joint_state);
227 }
228 
229 bool JointRelayHandler::convert_message(SimpleMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
230 {
231  JointMessage joint_msg;
232 
233  if (!joint_msg.init(msg_in))
234  {
235  LOG_ERROR("Failed to initialize joint message");
236  return false;
237  }
238 
239  return convert_message(joint_msg, joint_state, robot_id);
240 }
241 
242 bool JointRelayHandler::convert_message(JointMessage& msg_in, JointTrajectoryPoint* joint_state)
243 {
244  // copy position data
245  int num_jnts = all_joint_names_.size();
246  joint_state->positions.resize(num_jnts);
247  for (int i = 0; i < num_jnts; ++i)
248  {
250  if (msg_in.getJoints().getJoint(i, value))
251  {
252  joint_state->positions[i] = value;
253  }
254  else
255  LOG_ERROR("Failed to parse position #%d from JointMessage", i);
256  }
257 
258  // these fields are not provided by JointMessage
259  joint_state->velocities.clear();
260  joint_state->accelerations.clear();
261  joint_state->time_from_start = ros::Duration(0);
262 
263  return true;
264 }
265 
266 bool JointRelayHandler::convert_message(JointMessage& msg_in, DynamicJointsGroup* joint_state, int robot_id)
267 {
268  // copy position data
269  int num_jnts = robot_groups_[robot_id].get_joint_names().size();
270  joint_state->positions.resize(num_jnts);
271  for (int i = 0; i < num_jnts; ++i)
272  {
274  if (msg_in.getJoints().getJoint(i, value))
275  {
276  joint_state->positions[i] = value;
277  }
278  else
279  LOG_ERROR("Failed to convert message");
280  }
281 
282  // these fields are not provided by JointMessage
283  joint_state->velocities.clear();
284  joint_state->accelerations.clear();
285  joint_state->time_from_start = ros::Duration(0);
286 
287  return true;
288 }
289 
290 bool JointRelayHandler::select(const JointTrajectoryPoint& all_joint_state,
291  const std::vector<std::string>& all_joint_names, JointTrajectoryPoint* pub_joint_state,
292  std::vector<std::string>* pub_joint_names)
293 {
294  ROS_ASSERT(all_joint_state.positions.size() == all_joint_names.size());
295 
296  *pub_joint_state = JointTrajectoryPoint(); // start with a "clean" message
297  pub_joint_names->clear();
298 
299  // skip over "blank" joint names
300  for (size_t i = 0; i < all_joint_names.size(); ++i)
301  {
302  if (all_joint_names[i].empty())
303  continue;
304 
305  pub_joint_names->push_back(all_joint_names[i]);
306  if (!all_joint_state.positions.empty())
307  pub_joint_state->positions.push_back(all_joint_state.positions[i]);
308  if (!all_joint_state.velocities.empty())
309  pub_joint_state->velocities.push_back(all_joint_state.velocities[i]);
310  if (!all_joint_state.accelerations.empty())
311  pub_joint_state->accelerations.push_back(all_joint_state.accelerations[i]);
312  }
313  pub_joint_state->time_from_start = all_joint_state.time_from_start;
314 
315  return true;
316 }
317 
318 bool JointRelayHandler::select(const DynamicJointsGroup& all_joint_state,
319  const std::vector<std::string>& all_joint_names, DynamicJointsGroup* pub_joint_state,
320  std::vector<std::string>* pub_joint_names)
321 {
322  ROS_ASSERT(all_joint_state.positions.size() == all_joint_names.size());
323 
324  *pub_joint_state = DynamicJointsGroup(); // start with a "clean" message
325  pub_joint_names->clear();
326 
327  // skip over "blank" joint names
328  for (size_t i = 0; i < all_joint_names.size(); ++i)
329  {
330  if (all_joint_names[i].empty())
331  continue;
332  pub_joint_names->push_back(all_joint_names[i]);
333  if (!all_joint_state.positions.empty())
334  pub_joint_state->positions.push_back(all_joint_state.positions[i]);
335  if (!all_joint_state.velocities.empty())
336  pub_joint_state->velocities.push_back(all_joint_state.velocities[i]);
337  if (!all_joint_state.accelerations.empty())
338  pub_joint_state->accelerations.push_back(all_joint_state.accelerations[i]);
339  }
340  pub_joint_state->time_from_start = all_joint_state.time_from_start;
341 
342  return true;
343 }
344 
345 } // namespace joint_relay_handler
346 } // namespace industrial_robot_client
347 
348 
349 
350 
virtual bool sendMsg(industrial::simple_message::SimpleMessage &message)
bool init(industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
void publish(const boost::shared_ptr< M > &message) const
virtual bool create_messages(JointMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
virtual bool transform(const std::vector< double > &pos_in, std::vector< double > *pos_out)
UINT32 value
virtual bool select(const std::vector< double > &all_joint_pos, const std::vector< std::string > &all_joint_names, std::vector< double > *pub_joint_pos, std::vector< std::string > *pub_joint_names)
#define LOG_ERROR(format,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
industrial::smpl_msg_connection::SmplMsgConnection * getConnection()
static Time now()
#define ROS_ASSERT(cond)


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:43