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