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