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 // ********************************************
48 // * Internal (hidden) functions
49 // ********************************************
50 
51 namespace
52 {
53 static bool _jointStateToRobotState(const sensor_msgs::JointState& joint_state, RobotState& state)
54 {
55  if (joint_state.name.size() != joint_state.position.size())
56  {
57  CONSOLE_BRIDGE_logError("Different number of names and positions in JointState message: %zu, %zu",
58  joint_state.name.size(), joint_state.position.size());
59  return false;
60  }
61 
62  state.setVariableValues(joint_state);
63 
64  return true;
65 }
66 
67 static bool _multiDOFJointsToRobotState(const sensor_msgs::MultiDOFJointState& mjs, RobotState& state,
68  const Transforms* tf)
69 {
70  std::size_t nj = mjs.joint_names.size();
71  if (nj != mjs.transforms.size())
72  {
73  CONSOLE_BRIDGE_logError("Different number of names, values or frames in MultiDOFJointState message.");
74  return false;
75  }
76 
77  bool error = false;
78  Eigen::Affine3d inv_t;
79  bool use_inv_t = false;
80 
81  if (nj > 0 && !Transforms::sameFrame(mjs.header.frame_id, state.getRobotModel()->getModelFrame()))
82  {
83  if (tf)
84  try
85  {
86  // find the transform that takes the given frame_id to the desired fixed frame
87  const Eigen::Affine3d& t2fixed_frame = tf->getTransform(mjs.header.frame_id);
88  // we update the value of the transform so that it transforms from the known fixed frame to the desired child
89  // link
90  inv_t = t2fixed_frame.inverse();
91  use_inv_t = true;
92  }
93  catch (std::exception& ex)
94  {
95  CONSOLE_BRIDGE_logError("Caught %s", ex.what());
96  error = true;
97  }
98  else
99  error = true;
100 
101  if (error)
102  CONSOLE_BRIDGE_logWarn("The transform for multi-dof joints was specified in frame '%s' "
103  "but it was not possible to transform that to frame '%s'",
104  mjs.header.frame_id.c_str(), state.getRobotModel()->getModelFrame().c_str());
105  }
106 
107  for (std::size_t i = 0; i < nj; ++i)
108  {
109  const std::string& joint_name = mjs.joint_names[i];
110  if (!state.getRobotModel()->hasJointModel(joint_name))
111  {
112  CONSOLE_BRIDGE_logWarn("No joint matching multi-dof joint '%s'", joint_name.c_str());
113  error = true;
114  continue;
115  }
116  Eigen::Affine3d transf;
117  tf::transformMsgToEigen(mjs.transforms[i], transf);
118  // if frames do not mach, attempt to transform
119  if (use_inv_t)
120  transf = transf * inv_t;
121 
122  state.setJointPositions(joint_name, transf);
123  }
124 
125  return !error;
126 }
127 
128 static inline void _robotStateToMultiDOFJointState(const RobotState& state, sensor_msgs::MultiDOFJointState& mjs)
129 {
130  const std::vector<const JointModel*>& js = state.getRobotModel()->getMultiDOFJointModels();
131  mjs.joint_names.clear();
132  mjs.transforms.clear();
133  for (std::size_t i = 0; i < js.size(); ++i)
134  {
135  geometry_msgs::Transform p;
136  if (state.dirtyJointTransform(js[i]))
137  {
138  Eigen::Affine3d t;
139  t.setIdentity();
140  js[i]->computeTransform(state.getJointPositions(js[i]), t);
142  }
143  else
144  tf::transformEigenToMsg(state.getJointTransform(js[i]), p);
145  mjs.joint_names.push_back(js[i]->getName());
146  mjs.transforms.push_back(p);
147  }
148  mjs.header.frame_id = state.getRobotModel()->getModelFrame();
149 }
150 
151 class ShapeVisitorAddToCollisionObject : public boost::static_visitor<void>
152 {
153 public:
154  ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) : boost::static_visitor<void>(), obj_(obj)
155  {
156  }
157 
158  void addToObject(const shapes::ShapeMsg& sm, const geometry_msgs::Pose& pose)
159  {
160  pose_ = &pose;
161  boost::apply_visitor(*this, sm);
162  }
163 
164  void operator()(const shape_msgs::Plane& shape_msg) const
165  {
166  obj_->planes.push_back(shape_msg);
167  obj_->plane_poses.push_back(*pose_);
168  }
169 
170  void operator()(const shape_msgs::Mesh& shape_msg) const
171  {
172  obj_->meshes.push_back(shape_msg);
173  obj_->mesh_poses.push_back(*pose_);
174  }
175 
176  void operator()(const shape_msgs::SolidPrimitive& shape_msg) const
177  {
178  obj_->primitives.push_back(shape_msg);
179  obj_->primitive_poses.push_back(*pose_);
180  }
181 
182 private:
183  moveit_msgs::CollisionObject* obj_;
184  const geometry_msgs::Pose* pose_;
185 };
186 
187 static void _attachedBodyToMsg(const AttachedBody& attached_body, moveit_msgs::AttachedCollisionObject& aco)
188 {
189  aco.link_name = attached_body.getAttachedLinkName();
190  aco.detach_posture = attached_body.getDetachPosture();
191  const std::set<std::string>& touch_links = attached_body.getTouchLinks();
192  aco.touch_links.clear();
193  for (std::set<std::string>::const_iterator it = touch_links.begin(); it != touch_links.end(); ++it)
194  aco.touch_links.push_back(*it);
195  aco.object.header.frame_id = aco.link_name;
196  aco.object.id = attached_body.getName();
197 
198  aco.object.operation = moveit_msgs::CollisionObject::ADD;
199  const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body.getShapes();
200  const EigenSTL::vector_Affine3d& ab_tf = attached_body.getFixedTransforms();
201  ShapeVisitorAddToCollisionObject sv(&aco.object);
202  aco.object.primitives.clear();
203  aco.object.meshes.clear();
204  aco.object.planes.clear();
205  aco.object.primitive_poses.clear();
206  aco.object.mesh_poses.clear();
207  aco.object.plane_poses.clear();
208  for (std::size_t j = 0; j < ab_shapes.size(); ++j)
209  {
210  shapes::ShapeMsg sm;
211  if (shapes::constructMsgFromShape(ab_shapes[j].get(), sm))
212  {
213  geometry_msgs::Pose p;
214  tf::poseEigenToMsg(ab_tf[j], p);
215  sv.addToObject(sm, p);
216  }
217  }
218 }
219 
220 static void _msgToAttachedBody(const Transforms* tf, const moveit_msgs::AttachedCollisionObject& aco, RobotState& state)
221 {
222  if (aco.object.operation == moveit_msgs::CollisionObject::ADD)
223  {
224  if (!aco.object.primitives.empty() || !aco.object.meshes.empty() || !aco.object.planes.empty())
225  {
226  if (aco.object.primitives.size() != aco.object.primitive_poses.size())
227  {
228  CONSOLE_BRIDGE_logError("Number of primitive shapes does not match "
229  "number of poses in collision object message");
230  return;
231  }
232 
233  if (aco.object.meshes.size() != aco.object.mesh_poses.size())
234  {
235  CONSOLE_BRIDGE_logError("Number of meshes does not match number of poses in collision object message");
236  return;
237  }
238 
239  if (aco.object.planes.size() != aco.object.plane_poses.size())
240  {
241  CONSOLE_BRIDGE_logError("Number of planes does not match number of poses in collision object message");
242  return;
243  }
244 
245  const LinkModel* lm = state.getLinkModel(aco.link_name);
246  if (lm)
247  {
248  std::vector<shapes::ShapeConstPtr> shapes;
250 
251  for (std::size_t i = 0; i < aco.object.primitives.size(); ++i)
252  {
253  shapes::Shape* s = shapes::constructShapeFromMsg(aco.object.primitives[i]);
254  if (s)
255  {
256  Eigen::Affine3d p;
257  tf::poseMsgToEigen(aco.object.primitive_poses[i], p);
258  shapes.push_back(shapes::ShapeConstPtr(s));
259  poses.push_back(p);
260  }
261  }
262  for (std::size_t i = 0; i < aco.object.meshes.size(); ++i)
263  {
264  shapes::Shape* s = shapes::constructShapeFromMsg(aco.object.meshes[i]);
265  if (s)
266  {
267  Eigen::Affine3d p;
268  tf::poseMsgToEigen(aco.object.mesh_poses[i], p);
269  shapes.push_back(shapes::ShapeConstPtr(s));
270  poses.push_back(p);
271  }
272  }
273  for (std::size_t i = 0; i < aco.object.planes.size(); ++i)
274  {
275  shapes::Shape* s = shapes::constructShapeFromMsg(aco.object.planes[i]);
276  if (s)
277  {
278  Eigen::Affine3d p;
279  tf::poseMsgToEigen(aco.object.plane_poses[i], p);
280 
281  shapes.push_back(shapes::ShapeConstPtr(s));
282  poses.push_back(p);
283  }
284  }
285 
286  // transform poses to link frame
287  if (!Transforms::sameFrame(aco.object.header.frame_id, aco.link_name))
288  {
289  Eigen::Affine3d t0;
290  if (state.knowsFrameTransform(aco.object.header.frame_id))
291  t0 = state.getFrameTransform(aco.object.header.frame_id);
292  else if (tf && tf->canTransform(aco.object.header.frame_id))
293  t0 = tf->getTransform(aco.object.header.frame_id);
294  else
295  {
296  t0.setIdentity();
297  CONSOLE_BRIDGE_logError("Cannot properly transform from frame '%s'. "
298  "The pose of the attached body may be incorrect",
299  aco.object.header.frame_id.c_str());
300  }
301  Eigen::Affine3d t = state.getGlobalLinkTransform(lm).inverse() * t0;
302  for (std::size_t i = 0; i < poses.size(); ++i)
303  poses[i] = t * poses[i];
304  }
305 
306  if (shapes.empty())
307  CONSOLE_BRIDGE_logError("There is no geometry to attach to link '%s' as part of attached body '%s'",
308  aco.link_name.c_str(), aco.object.id.c_str());
309  else
310  {
311  if (state.clearAttachedBody(aco.object.id))
312  CONSOLE_BRIDGE_logDebug("The robot state already had an object named '%s' attached to link '%s'. "
313  "The object was replaced.",
314  aco.object.id.c_str(), aco.link_name.c_str());
315  state.attachBody(aco.object.id, shapes, poses, aco.touch_links, aco.link_name, aco.detach_posture);
316  CONSOLE_BRIDGE_logDebug("Attached object '%s' to link '%s'", aco.object.id.c_str(), aco.link_name.c_str());
317  }
318  }
319  }
320  else
321  CONSOLE_BRIDGE_logError("The attached body for link '%s' has no geometry", aco.link_name.c_str());
322  }
323  else if (aco.object.operation == moveit_msgs::CollisionObject::REMOVE)
324  {
325  if (!state.clearAttachedBody(aco.object.id))
326  CONSOLE_BRIDGE_logError("The attached body '%s' can not be removed because it does not exist",
327  aco.link_name.c_str());
328  }
329  else
330  CONSOLE_BRIDGE_logError("Unknown collision object operation: %d", aco.object.operation);
331 }
332 
333 static bool _robotStateMsgToRobotStateHelper(const Transforms* tf, const moveit_msgs::RobotState& robot_state,
334  RobotState& state, bool copy_attached_bodies)
335 {
336  bool valid;
337  const moveit_msgs::RobotState& rs = robot_state;
338 
339  if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
340  {
341  CONSOLE_BRIDGE_logError("Found empty JointState message");
342  return false;
343  }
344 
345  bool result1 = _jointStateToRobotState(robot_state.joint_state, state);
346  bool result2 = _multiDOFJointsToRobotState(robot_state.multi_dof_joint_state, state, tf);
347  valid = result1 || result2;
348 
349  if (valid && copy_attached_bodies)
350  {
351  if (!robot_state.is_diff)
352  state.clearAttachedBodies();
353  for (std::size_t i = 0; i < robot_state.attached_collision_objects.size(); ++i)
354  _msgToAttachedBody(tf, robot_state.attached_collision_objects[i], state);
355  }
356 
357  return valid;
358 }
359 }
360 }
361 }
362 
363 // ********************************************
364 
365 // ********************************************
366 // * Exposed functions
367 // ********************************************
368 
369 bool moveit::core::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 moveit::core::robotStateMsgToRobotState(const moveit_msgs::RobotState& robot_state, RobotState& state,
377  bool copy_attached_bodies)
378 {
379  bool result = _robotStateMsgToRobotStateHelper(NULL, robot_state, state, copy_attached_bodies);
380  state.update();
381  return result;
382 }
383 
384 bool moveit::core::robotStateMsgToRobotState(const Transforms& tf, const moveit_msgs::RobotState& robot_state,
385  RobotState& state, bool copy_attached_bodies)
386 {
387  bool result = _robotStateMsgToRobotStateHelper(&tf, robot_state, state, copy_attached_bodies);
388  state.update();
389  return result;
390 }
391 
392 void moveit::core::robotStateToRobotStateMsg(const RobotState& state, moveit_msgs::RobotState& robot_state,
393  bool copy_attached_bodies)
394 {
395  robotStateToJointStateMsg(state, robot_state.joint_state);
396  _robotStateToMultiDOFJointState(state, robot_state.multi_dof_joint_state);
397 
398  if (copy_attached_bodies)
399  {
400  std::vector<const AttachedBody*> attached_bodies;
401  state.getAttachedBodies(attached_bodies);
402  attachedBodiesToAttachedCollisionObjectMsgs(attached_bodies, robot_state.attached_collision_objects);
403  }
404 }
405 
407  const std::vector<const AttachedBody*>& attached_bodies,
408  std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
409 {
410  attached_collision_objs.resize(attached_bodies.size());
411  for (std::size_t i = 0; i < attached_bodies.size(); ++i)
412  _attachedBodyToMsg(*attached_bodies[i], attached_collision_objs[i]);
413 }
414 
415 void moveit::core::robotStateToJointStateMsg(const RobotState& state, sensor_msgs::JointState& joint_state)
416 {
417  const std::vector<const JointModel*>& js = state.getRobotModel()->getSingleDOFJointModels();
418  joint_state = sensor_msgs::JointState();
419 
420  for (std::size_t i = 0; i < js.size(); ++i)
421  {
422  joint_state.name.push_back(js[i]->getName());
423  joint_state.position.push_back(state.getVariablePosition(js[i]->getFirstVariableIndex()));
424  if (state.hasVelocities())
425  joint_state.velocity.push_back(state.getVariableVelocity(js[i]->getFirstVariableIndex()));
426  }
427 
428  // if inconsistent number of velocities are specified, discard them
429  if (joint_state.velocity.size() != joint_state.position.size())
430  joint_state.velocity.clear();
431 
432  joint_state.header.frame_id = state.getRobotModel()->getModelFrame();
433 }
434 
435 bool moveit::core::jointTrajPointToRobotState(const trajectory_msgs::JointTrajectory& trajectory, std::size_t point_id,
436  RobotState& state)
437 {
438  if (trajectory.points.empty() || point_id > trajectory.points.size() - 1)
439  {
440  CONSOLE_BRIDGE_logError("Invalid point_id");
441  return false;
442  }
443  if (trajectory.joint_names.empty())
444  {
445  CONSOLE_BRIDGE_logError("No joint names specified");
446  return false;
447  }
448 
449  state.setVariablePositions(trajectory.joint_names, trajectory.points[point_id].positions);
450  if (!trajectory.points[point_id].velocities.empty())
451  state.setVariableVelocities(trajectory.joint_names, trajectory.points[point_id].velocities);
452  if (!trajectory.points[point_id].accelerations.empty())
453  state.setVariableAccelerations(trajectory.joint_names, trajectory.points[point_id].accelerations);
454  if (!trajectory.points[point_id].effort.empty())
455  state.setVariableEffort(trajectory.joint_names, trajectory.points[point_id].effort);
456 
457  return true;
458 }
459 
460 void moveit::core::robotStateToStream(const RobotState& state, std::ostream& out, bool include_header,
461  const std::string& separator)
462 {
463  // Output name of variables
464  if (include_header)
465  {
466  for (std::size_t i = 0; i < state.getVariableCount(); ++i)
467  {
468  out << state.getVariableNames()[i];
469 
470  // Output comma except at end
471  if (i < state.getVariableCount() - 1)
472  out << separator;
473  }
474  out << std::endl;
475  }
476 
477  // Output values of joints
478  for (std::size_t i = 0; i < state.getVariableCount(); ++i)
479  {
480  out << state.getVariablePositions()[i];
481 
482  // Output comma except at end
483  if (i < state.getVariableCount() - 1)
484  out << separator;
485  }
486  out << std::endl;
487 }
488 
489 void moveit::core::robotStateToStream(const RobotState& state, std::ostream& out,
490  const std::vector<std::string>& joint_groups_ordering, bool include_header,
491  const std::string& separator)
492 {
493  std::stringstream headers;
494  std::stringstream joints;
495 
496  for (std::size_t j = 0; j < joint_groups_ordering.size(); ++j)
497  {
498  const JointModelGroup* jmg = state.getRobotModel()->getJointModelGroup(joint_groups_ordering[j]);
499 
500  // Output name of variables
501  if (include_header)
502  {
503  for (std::size_t i = 0; i < jmg->getVariableCount(); ++i)
504  {
505  headers << jmg->getVariableNames()[i] << separator;
506  }
507  }
508 
509  // Copy the joint positions for each joint model group
510  std::vector<double> group_variable_positions;
511  state.copyJointGroupPositions(jmg, group_variable_positions);
512 
513  // Output values of joints
514  for (std::size_t i = 0; i < jmg->getVariableCount(); ++i)
515  {
516  joints << group_variable_positions[i] << separator;
517  }
518  }
519 
520  // Push all headers and joints to our output stream
521  if (include_header)
522  out << headers.str() << std::endl;
523  out << joints.str() << std::endl;
524 }
525 
526 void moveit::core::streamToRobotState(RobotState& state, const std::string& line, const std::string& separator)
527 {
528  std::stringstream lineStream(line);
529  std::string cell;
530 
531  // For each item/column
532  for (std::size_t i = 0; i < state.getVariableCount(); ++i)
533  {
534  // Get a variable
535  if (!std::getline(lineStream, cell, separator[0]))
536  CONSOLE_BRIDGE_logError("Missing variable %i", i);
537 
538  state.getVariablePositions()[i] = boost::lexical_cast<double>(cell.c_str());
539  }
540 }
#define CONSOLE_BRIDGE_logWarn(fmt,...)
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...
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
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:271
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:250
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:59
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.
#define CONSOLE_BRIDGE_logDebug(fmt,...)
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:168
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:660
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
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:125
const geometry_msgs::Pose * pose_
#define CONSOLE_BRIDGE_logError(fmt,...)
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:360
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:110
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:228
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:451
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:137
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:131
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:314
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 Sat Apr 21 2018 02:54:51