conversions.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Ioan A. Sucan
5 * Copyright (c) 2011-2013, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
36 /* Author: Ioan Sucan, Dave Coleman */
37 
41 #include <boost/lexical_cast.hpp>
42 
43 namespace moveit
44 {
45 namespace core
46 {
47 const std::string LOGNAME = "robot_state";
48 
49 // ********************************************
50 // * Internal (hidden) functions
51 // ********************************************
52 
53 namespace
54 {
55 static bool _jointStateToRobotState(const sensor_msgs::JointState& joint_state, RobotState& state)
56 {
57  if (joint_state.name.size() != joint_state.position.size())
58  {
59  ROS_ERROR_NAMED(LOGNAME, "Different number of names and positions in JointState message: %zu, %zu",
60  joint_state.name.size(), joint_state.position.size());
61  return false;
62  }
63 
64  state.setVariableValues(joint_state);
65 
66  return true;
67 }
68 
69 static bool _multiDOFJointsToRobotState(const sensor_msgs::MultiDOFJointState& mjs, RobotState& state,
70  const Transforms* tf)
71 {
72  std::size_t nj = mjs.joint_names.size();
73  if (nj != mjs.transforms.size())
74  {
75  ROS_ERROR_NAMED(LOGNAME, "Different number of names, values or frames in MultiDOFJointState message.");
76  return false;
77  }
78 
79  bool error = false;
80  Eigen::Affine3d inv_t;
81  bool use_inv_t = false;
82 
83  if (nj > 0 && !Transforms::sameFrame(mjs.header.frame_id, state.getRobotModel()->getModelFrame()))
84  {
85  if (tf)
86  try
87  {
88  // find the transform that takes the given frame_id to the desired fixed frame
89  const Eigen::Affine3d& t2fixed_frame = tf->getTransform(mjs.header.frame_id);
90  // we update the value of the transform so that it transforms from the known fixed frame to the desired child
91  // link
92  inv_t = t2fixed_frame.inverse(Eigen::Isometry);
93  use_inv_t = true;
94  }
95  catch (std::exception& ex)
96  {
97  ROS_ERROR_NAMED(LOGNAME, "Caught %s", ex.what());
98  error = true;
99  }
100  else
101  error = true;
102 
103  if (error)
104  ROS_WARN_NAMED(LOGNAME, "The transform for multi-dof joints was specified in frame '%s' "
105  "but it was not possible to transform that to frame '%s'",
106  mjs.header.frame_id.c_str(), state.getRobotModel()->getModelFrame().c_str());
107  }
108 
109  for (std::size_t i = 0; i < nj; ++i)
110  {
111  const std::string& joint_name = mjs.joint_names[i];
112  if (!state.getRobotModel()->hasJointModel(joint_name))
113  {
114  ROS_WARN_NAMED(LOGNAME, "No joint matching multi-dof joint '%s'", joint_name.c_str());
115  error = true;
116  continue;
117  }
118  Eigen::Affine3d transf;
119  tf::transformMsgToEigen(mjs.transforms[i], transf);
120  // if frames do not mach, attempt to transform
121  if (use_inv_t)
122  transf = transf * inv_t;
123 
124  state.setJointPositions(joint_name, transf);
125  }
126 
127  return !error;
128 }
129 
130 static inline void _robotStateToMultiDOFJointState(const RobotState& state, sensor_msgs::MultiDOFJointState& mjs)
131 {
132  const std::vector<const JointModel*>& js = state.getRobotModel()->getMultiDOFJointModels();
133  mjs.joint_names.clear();
134  mjs.transforms.clear();
135  for (std::size_t i = 0; i < js.size(); ++i)
136  {
137  geometry_msgs::Transform p;
138  if (state.dirtyJointTransform(js[i]))
139  {
140  Eigen::Affine3d t;
141  t.setIdentity();
142  js[i]->computeTransform(state.getJointPositions(js[i]), t);
144  }
145  else
146  tf::transformEigenToMsg(state.getJointTransform(js[i]), p);
147  mjs.joint_names.push_back(js[i]->getName());
148  mjs.transforms.push_back(p);
149  }
150  mjs.header.frame_id = state.getRobotModel()->getModelFrame();
151 }
152 
153 class ShapeVisitorAddToCollisionObject : public boost::static_visitor<void>
154 {
155 public:
156  ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) : boost::static_visitor<void>(), obj_(obj)
157  {
158  }
159 
160  void addToObject(const shapes::ShapeMsg& sm, const geometry_msgs::Pose& pose)
161  {
162  pose_ = &pose;
163  boost::apply_visitor(*this, sm);
164  }
165 
166  void operator()(const shape_msgs::Plane& shape_msg) const
167  {
168  obj_->planes.push_back(shape_msg);
169  obj_->plane_poses.push_back(*pose_);
170  }
171 
172  void operator()(const shape_msgs::Mesh& shape_msg) const
173  {
174  obj_->meshes.push_back(shape_msg);
175  obj_->mesh_poses.push_back(*pose_);
176  }
177 
178  void operator()(const shape_msgs::SolidPrimitive& shape_msg) const
179  {
180  obj_->primitives.push_back(shape_msg);
181  obj_->primitive_poses.push_back(*pose_);
182  }
183 
184 private:
185  moveit_msgs::CollisionObject* obj_;
186  const geometry_msgs::Pose* pose_;
187 };
188 
189 static void _attachedBodyToMsg(const AttachedBody& attached_body, moveit_msgs::AttachedCollisionObject& aco)
190 {
191  aco.link_name = attached_body.getAttachedLinkName();
192  aco.detach_posture = attached_body.getDetachPosture();
193  const std::set<std::string>& touch_links = attached_body.getTouchLinks();
194  aco.touch_links.clear();
195  for (std::set<std::string>::const_iterator it = touch_links.begin(); it != touch_links.end(); ++it)
196  aco.touch_links.push_back(*it);
197  aco.object.header.frame_id = aco.link_name;
198  aco.object.id = attached_body.getName();
199 
200  aco.object.operation = moveit_msgs::CollisionObject::ADD;
201  const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body.getShapes();
202  const EigenSTL::vector_Affine3d& ab_tf = attached_body.getFixedTransforms();
203  ShapeVisitorAddToCollisionObject sv(&aco.object);
204  aco.object.primitives.clear();
205  aco.object.meshes.clear();
206  aco.object.planes.clear();
207  aco.object.primitive_poses.clear();
208  aco.object.mesh_poses.clear();
209  aco.object.plane_poses.clear();
210  for (std::size_t j = 0; j < ab_shapes.size(); ++j)
211  {
212  shapes::ShapeMsg sm;
213  if (shapes::constructMsgFromShape(ab_shapes[j].get(), sm))
214  {
215  geometry_msgs::Pose p;
216  tf::poseEigenToMsg(ab_tf[j], p);
217  sv.addToObject(sm, p);
218  }
219  }
220 }
221 
222 static void _msgToAttachedBody(const Transforms* tf, const moveit_msgs::AttachedCollisionObject& aco, RobotState& state)
223 {
224  if (aco.object.operation == moveit_msgs::CollisionObject::ADD)
225  {
226  if (!aco.object.primitives.empty() || !aco.object.meshes.empty() || !aco.object.planes.empty())
227  {
228  if (aco.object.primitives.size() != aco.object.primitive_poses.size())
229  {
230  ROS_ERROR_NAMED(LOGNAME, "Number of primitive shapes does not match "
231  "number of poses in collision object message");
232  return;
233  }
234 
235  if (aco.object.meshes.size() != aco.object.mesh_poses.size())
236  {
237  ROS_ERROR_NAMED(LOGNAME, "Number of meshes does not match number of poses in collision object message");
238  return;
239  }
240 
241  if (aco.object.planes.size() != aco.object.plane_poses.size())
242  {
243  ROS_ERROR_NAMED(LOGNAME, "Number of planes does not match number of poses in collision object message");
244  return;
245  }
246 
247  const LinkModel* lm = state.getLinkModel(aco.link_name);
248  if (lm)
249  {
250  std::vector<shapes::ShapeConstPtr> shapes;
252 
253  for (std::size_t i = 0; i < aco.object.primitives.size(); ++i)
254  {
255  shapes::Shape* s = shapes::constructShapeFromMsg(aco.object.primitives[i]);
256  if (s)
257  {
258  Eigen::Affine3d p;
259  tf::poseMsgToEigen(aco.object.primitive_poses[i], p);
260  shapes.push_back(shapes::ShapeConstPtr(s));
261  poses.push_back(p);
262  }
263  }
264  for (std::size_t i = 0; i < aco.object.meshes.size(); ++i)
265  {
266  shapes::Shape* s = shapes::constructShapeFromMsg(aco.object.meshes[i]);
267  if (s)
268  {
269  Eigen::Affine3d p;
270  tf::poseMsgToEigen(aco.object.mesh_poses[i], p);
271  shapes.push_back(shapes::ShapeConstPtr(s));
272  poses.push_back(p);
273  }
274  }
275  for (std::size_t i = 0; i < aco.object.planes.size(); ++i)
276  {
277  shapes::Shape* s = shapes::constructShapeFromMsg(aco.object.planes[i]);
278  if (s)
279  {
280  Eigen::Affine3d p;
281  tf::poseMsgToEigen(aco.object.plane_poses[i], p);
282 
283  shapes.push_back(shapes::ShapeConstPtr(s));
284  poses.push_back(p);
285  }
286  }
287 
288  // transform poses to link frame
289  if (!Transforms::sameFrame(aco.object.header.frame_id, aco.link_name))
290  {
291  Eigen::Affine3d t0;
292  if (state.knowsFrameTransform(aco.object.header.frame_id))
293  t0 = state.getFrameTransform(aco.object.header.frame_id);
294  else if (tf && tf->canTransform(aco.object.header.frame_id))
295  t0 = tf->getTransform(aco.object.header.frame_id);
296  else
297  {
298  t0.setIdentity();
299  ROS_ERROR_NAMED(LOGNAME, "Cannot properly transform from frame '%s'. "
300  "The pose of the attached body may be incorrect",
301  aco.object.header.frame_id.c_str());
302  }
303  Eigen::Affine3d t = state.getGlobalLinkTransform(lm).inverse(Eigen::Isometry) * t0;
304  for (std::size_t i = 0; i < poses.size(); ++i)
305  poses[i] = t * poses[i];
306  }
307 
308  if (shapes.empty())
309  ROS_ERROR_NAMED(LOGNAME, "There is no geometry to attach to link '%s' as part of attached body '%s'",
310  aco.link_name.c_str(), aco.object.id.c_str());
311  else
312  {
313  if (state.clearAttachedBody(aco.object.id))
314  ROS_DEBUG_NAMED(LOGNAME, "The robot state already had an object named '%s' attached to link '%s'. "
315  "The object was replaced.",
316  aco.object.id.c_str(), aco.link_name.c_str());
317  state.attachBody(aco.object.id, shapes, poses, aco.touch_links, aco.link_name, aco.detach_posture);
318  ROS_DEBUG_NAMED(LOGNAME, "Attached object '%s' to link '%s'", aco.object.id.c_str(), aco.link_name.c_str());
319  }
320  }
321  }
322  else
323  ROS_ERROR_NAMED(LOGNAME, "The attached body for link '%s' has no geometry", aco.link_name.c_str());
324  }
325  else if (aco.object.operation == moveit_msgs::CollisionObject::REMOVE)
326  {
327  if (!state.clearAttachedBody(aco.object.id))
328  ROS_ERROR_NAMED(LOGNAME, "The attached body '%s' can not be removed because it does not exist",
329  aco.link_name.c_str());
330  }
331  else
332  ROS_ERROR_NAMED(LOGNAME, "Unknown collision object operation: %d", aco.object.operation);
333 }
334 
335 static bool _robotStateMsgToRobotStateHelper(const Transforms* tf, const moveit_msgs::RobotState& robot_state,
336  RobotState& state, bool copy_attached_bodies)
337 {
338  bool valid;
339  const moveit_msgs::RobotState& rs = robot_state;
340 
341  if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
342  {
343  ROS_ERROR_NAMED(LOGNAME, "Found empty JointState message");
344  return false;
345  }
346 
347  bool result1 = _jointStateToRobotState(robot_state.joint_state, state);
348  bool result2 = _multiDOFJointsToRobotState(robot_state.multi_dof_joint_state, state, tf);
349  valid = result1 || result2;
350 
351  if (valid && copy_attached_bodies)
352  {
353  if (!robot_state.is_diff)
354  state.clearAttachedBodies();
355  for (std::size_t i = 0; i < robot_state.attached_collision_objects.size(); ++i)
356  _msgToAttachedBody(tf, robot_state.attached_collision_objects[i], state);
357  }
358 
359  return valid;
360 }
361 }
362 
363 // ********************************************
364 
365 // ********************************************
366 // * Exposed functions
367 // ********************************************
368 
369 bool jointStateToRobotState(const sensor_msgs::JointState& joint_state, RobotState& state)
370 {
371  bool result = _jointStateToRobotState(joint_state, state);
372  state.update();
373  return result;
374 }
375 
376 bool robotStateMsgToRobotState(const moveit_msgs::RobotState& robot_state, RobotState& state, bool copy_attached_bodies)
377 {
378  bool result = _robotStateMsgToRobotStateHelper(nullptr, robot_state, state, copy_attached_bodies);
379  state.update();
380  return result;
381 }
382 
383 bool robotStateMsgToRobotState(const Transforms& tf, const moveit_msgs::RobotState& robot_state, RobotState& state,
384  bool copy_attached_bodies)
385 {
386  bool result = _robotStateMsgToRobotStateHelper(&tf, robot_state, state, copy_attached_bodies);
387  state.update();
388  return result;
389 }
390 
391 void robotStateToRobotStateMsg(const RobotState& state, moveit_msgs::RobotState& robot_state, bool copy_attached_bodies)
392 {
393  robot_state.is_diff = false;
394  robotStateToJointStateMsg(state, robot_state.joint_state);
395  _robotStateToMultiDOFJointState(state, robot_state.multi_dof_joint_state);
396 
397  if (copy_attached_bodies)
398  {
399  std::vector<const AttachedBody*> attached_bodies;
400  state.getAttachedBodies(attached_bodies);
401  attachedBodiesToAttachedCollisionObjectMsgs(attached_bodies, robot_state.attached_collision_objects);
402  }
403 }
404 
406  const std::vector<const AttachedBody*>& attached_bodies,
407  std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
408 {
409  attached_collision_objs.resize(attached_bodies.size());
410  for (std::size_t i = 0; i < attached_bodies.size(); ++i)
411  _attachedBodyToMsg(*attached_bodies[i], attached_collision_objs[i]);
412 }
413 
414 void robotStateToJointStateMsg(const RobotState& state, sensor_msgs::JointState& joint_state)
415 {
416  const std::vector<const JointModel*>& js = state.getRobotModel()->getSingleDOFJointModels();
417  joint_state = sensor_msgs::JointState();
418 
419  for (std::size_t i = 0; i < js.size(); ++i)
420  {
421  joint_state.name.push_back(js[i]->getName());
422  joint_state.position.push_back(state.getVariablePosition(js[i]->getFirstVariableIndex()));
423  if (state.hasVelocities())
424  joint_state.velocity.push_back(state.getVariableVelocity(js[i]->getFirstVariableIndex()));
425  }
426 
427  // if inconsistent number of velocities are specified, discard them
428  if (joint_state.velocity.size() != joint_state.position.size())
429  joint_state.velocity.clear();
430 
431  joint_state.header.frame_id = state.getRobotModel()->getModelFrame();
432 }
433 
434 bool jointTrajPointToRobotState(const trajectory_msgs::JointTrajectory& trajectory, std::size_t point_id,
435  RobotState& state)
436 {
437  if (trajectory.points.empty() || point_id > trajectory.points.size() - 1)
438  {
439  ROS_ERROR_NAMED(LOGNAME, "Invalid point_id");
440  return false;
441  }
442  if (trajectory.joint_names.empty())
443  {
444  ROS_ERROR_NAMED(LOGNAME, "No joint names specified");
445  return false;
446  }
447 
448  state.setVariablePositions(trajectory.joint_names, trajectory.points[point_id].positions);
449  if (!trajectory.points[point_id].velocities.empty())
450  state.setVariableVelocities(trajectory.joint_names, trajectory.points[point_id].velocities);
451  if (!trajectory.points[point_id].accelerations.empty())
452  state.setVariableAccelerations(trajectory.joint_names, trajectory.points[point_id].accelerations);
453  if (!trajectory.points[point_id].effort.empty())
454  state.setVariableEffort(trajectory.joint_names, trajectory.points[point_id].effort);
455 
456  return true;
457 }
458 
459 void robotStateToStream(const RobotState& state, std::ostream& out, bool include_header, const std::string& separator)
460 {
461  // Output name of variables
462  if (include_header)
463  {
464  for (std::size_t i = 0; i < state.getVariableCount(); ++i)
465  {
466  out << state.getVariableNames()[i];
467 
468  // Output comma except at end
469  if (i < state.getVariableCount() - 1)
470  out << separator;
471  }
472  out << std::endl;
473  }
474 
475  // Output values of joints
476  for (std::size_t i = 0; i < state.getVariableCount(); ++i)
477  {
478  out << state.getVariablePositions()[i];
479 
480  // Output comma except at end
481  if (i < state.getVariableCount() - 1)
482  out << separator;
483  }
484  out << std::endl;
485 }
486 
487 void robotStateToStream(const RobotState& state, std::ostream& out,
488  const std::vector<std::string>& joint_groups_ordering, bool include_header,
489  const std::string& separator)
490 {
491  std::stringstream headers;
492  std::stringstream joints;
493 
494  for (std::size_t j = 0; j < joint_groups_ordering.size(); ++j)
495  {
496  const JointModelGroup* jmg = state.getRobotModel()->getJointModelGroup(joint_groups_ordering[j]);
497 
498  // Output name of variables
499  if (include_header)
500  {
501  for (std::size_t i = 0; i < jmg->getVariableCount(); ++i)
502  {
503  headers << jmg->getVariableNames()[i] << separator;
504  }
505  }
506 
507  // Copy the joint positions for each joint model group
508  std::vector<double> group_variable_positions;
509  state.copyJointGroupPositions(jmg, group_variable_positions);
510 
511  // Output values of joints
512  for (std::size_t i = 0; i < jmg->getVariableCount(); ++i)
513  {
514  joints << group_variable_positions[i] << separator;
515  }
516  }
517 
518  // Push all headers and joints to our output stream
519  if (include_header)
520  out << headers.str() << std::endl;
521  out << joints.str() << std::endl;
522 }
523 
524 void streamToRobotState(RobotState& state, const std::string& line, const std::string& separator)
525 {
526  std::stringstream lineStream(line);
527  std::string cell;
528 
529  // For each item/column
530  for (std::size_t i = 0; i < state.getVariableCount(); ++i)
531  {
532  // Get a variable
533  if (!std::getline(lineStream, cell, separator[0]))
534  ROS_ERROR_STREAM_NAMED(LOGNAME, "Missing variable " << state.getVariableNames()[i]);
535 
536  state.getVariablePositions()[i] = boost::lexical_cast<double>(cell.c_str());
537  }
538 }
539 
540 } // end of namespace core
541 } // end of namespace moveit
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
Core components of MoveIt!
void attachedBodiesToAttachedCollisionObjectMsgs(const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objs)
Convert AttachedBodies to AttachedCollisionObjects.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
#define ROS_WARN_NAMED(name,...)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
void robotStateToStream(const RobotState &state, std::ostream &out, bool include_header=true, const std::string &separator=",")
Convert a MoveIt! robot state to common separated values (CSV) on a single line that is outputted to ...
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
Definition: robot_state.h:284
XmlRpcServer s
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
Definition: robot_state.h:263
bool jointTrajPointToRobotState(const trajectory_msgs::JointTrajectory &trajectory, std::size_t point_id, RobotState &state)
Convert a joint trajectory point to a MoveIt! robot state.
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
Definition: transforms.cpp:64
std::string getName(void *handle)
void robotStateToJointStateMsg(const RobotState &state, sensor_msgs::JointState &joint_state)
Convert a MoveIt! robot state to a joint state message.
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully. If you change these values externally you need to make sure you trigger a forced update for the state by calling update(true).
Definition: robot_state.h:181
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state...
Provides an implementation of a snapshot of a transform tree that can be easily queried for transform...
Definition: transforms.h:61
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:666
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
#define ROS_DEBUG_NAMED(name,...)
void update(bool force=false)
Update all transforms.
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt! robot state...
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:138
const std::string LOGNAME
Definition: robot_model.cpp:53
const geometry_msgs::Pose * pose_
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt! robot state to a robot state message.
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
bool jointStateToRobotState(const sensor_msgs::JointState &joint_state, RobotState &state)
Convert a joint state to a MoveIt! robot state.
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
Definition: robot_state.h:373
#define ROS_ERROR_NAMED(name,...)
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known...
Definition: robot_state.h:241
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state...
Definition: robot_state.h:464
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up this state, in the order they are stored in memory...
Definition: robot_state.h:150
Main namespace for MoveIt!
moveit_msgs::CollisionObject * obj_
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:144
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known...
Definition: robot_state.h:327
void streamToRobotState(RobotState &state, const std::string &line, const std::string &separator=",")
Convert a string of joint values from a file (CSV) or input source into a RobotState.
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
std::shared_ptr< const Shape > ShapeConstPtr


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05