39 #include <geometric_shapes/shape_operations.h>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 #include <tf2_eigen/tf2_eigen.hpp>
56 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_robot_state.conversions");
58 static bool _jointStateToRobotState(
const sensor_msgs::msg::JointState& joint_state, RobotState& state)
60 if (joint_state.name.size() != joint_state.position.size())
62 RCLCPP_ERROR(LOGGER,
"Different number of names and positions in JointState message: %zu, %zu",
63 joint_state.name.size(), joint_state.position.size());
67 state.setVariableValues(joint_state);
72 static bool _multiDOFJointsToRobotState(
const sensor_msgs::msg::MultiDOFJointState& mjs, RobotState& state,
75 std::size_t nj = mjs.joint_names.size();
76 if (nj != mjs.transforms.size())
78 RCLCPP_ERROR(LOGGER,
"Different number of names, values or frames in MultiDOFJointState message.");
83 Eigen::Isometry3d inv_t;
84 bool use_inv_t =
false;
93 const Eigen::Isometry3d& t2fixed_frame = tf->getTransform(mjs.header.frame_id);
96 inv_t = t2fixed_frame.inverse();
99 catch (std::exception& ex)
101 RCLCPP_ERROR(LOGGER,
"Caught %s", ex.what());
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());
119 for (std::size_t i = 0; i < nj; ++i)
121 const std::string& joint_name = mjs.joint_names[i];
122 if (!state.getRobotModel()->hasJointModel(joint_name))
124 RCLCPP_WARN(LOGGER,
"No joint matching multi-dof joint '%s'", joint_name.c_str());
128 Eigen::Isometry3d transf = tf2::transformToEigen(mjs.transforms[i]);
131 transf = transf * inv_t;
133 state.setJointPositions(joint_name, transf);
139 static inline void _robotStateToMultiDOFJointState(
const RobotState& state, sensor_msgs::msg::MultiDOFJointState& mjs)
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)
146 geometry_msgs::msg::TransformStamped p;
147 if (state.dirtyJointTransform(joint_model))
151 joint_model->computeTransform(state.getJointPositions(joint_model), t);
152 p = tf2::eigenToTransform(t);
155 p = tf2::eigenToTransform(state.getJointTransform(joint_model));
156 mjs.joint_names.push_back(joint_model->getName());
157 mjs.transforms.push_back(p.transform);
159 mjs.header.frame_id = state.getRobotModel()->getModelFrame();
162 class ShapeVisitorAddToCollisionObject :
public boost::static_visitor<void>
165 ShapeVisitorAddToCollisionObject(moveit_msgs::msg::CollisionObject* obj) :
boost::static_visitor<void>(), obj_(obj)
169 void addToObject(
const shapes::ShapeMsg& sm,
const geometry_msgs::msg::Pose& pose)
172 boost::apply_visitor(*
this, sm);
175 void operator()(
const shape_msgs::msg::Plane& shape_msg)
const
177 obj_->planes.push_back(shape_msg);
178 obj_->plane_poses.push_back(*pose_);
181 void operator()(
const shape_msgs::msg::Mesh& shape_msg)
const
183 obj_->meshes.push_back(shape_msg);
184 obj_->mesh_poses.push_back(*pose_);
187 void operator()(
const shape_msgs::msg::SolidPrimitive& shape_msg)
const
189 obj_->primitives.push_back(shape_msg);
190 obj_->primitive_poses.push_back(*pose_);
194 moveit_msgs::msg::CollisionObject* obj_;
195 const geometry_msgs::msg::Pose* pose_;
198 static void _attachedBodyToMsg(
const AttachedBody& attached_body, moveit_msgs::msg::AttachedCollisionObject& aco)
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());
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)
223 if (shapes::constructMsgFromShape(ab_shapes[j].get(), sm))
225 geometry_msgs::msg::Pose p;
226 p = tf2::toMsg(shape_poses[j]);
227 sv.addToObject(sm, p);
230 aco.object.subframe_names.clear();
231 aco.object.subframe_poses.clear();
232 for (
const auto& frame_pair : attached_body.getSubframes())
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);
241 static void _msgToAttachedBody(
const Transforms* tf,
const moveit_msgs::msg::AttachedCollisionObject& aco,
244 if (aco.object.operation == moveit_msgs::msg::CollisionObject::ADD)
246 if (!aco.object.primitives.empty() || !aco.object.meshes.empty() || !aco.object.planes.empty())
248 if (aco.object.primitives.size() != aco.object.primitive_poses.size())
250 RCLCPP_ERROR(LOGGER,
"Number of primitive shapes does not match "
251 "number of poses in collision object message");
255 if (aco.object.meshes.size() != aco.object.mesh_poses.size())
257 RCLCPP_ERROR(LOGGER,
"Number of meshes does not match number of poses in collision object message");
261 if (aco.object.planes.size() != aco.object.plane_poses.size())
263 RCLCPP_ERROR(LOGGER,
"Number of planes does not match number of poses in collision object message");
267 if (aco.object.subframe_poses.size() != aco.object.subframe_names.size())
269 RCLCPP_ERROR(LOGGER,
"Number of subframe poses does not match number of subframe names in message");
273 const LinkModel* lm = state.getLinkModel(aco.link_name);
276 Eigen::Isometry3d object_pose;
277 tf2::fromMsg(aco.object.pose, object_pose);
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);
285 auto append = [&
shapes, &shape_poses](shapes::Shape* s,
const geometry_msgs::msg::Pose& pose_msg) {
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));
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]);
302 for (std::size_t i = 0; i < aco.object.subframe_poses.size(); ++i)
305 tf2::fromMsg(aco.object.subframe_poses[i], p);
306 std::string
name = aco.object.subframe_names[i];
307 subframe_poses[
name] = p;
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);
318 if (tf && tf->canTransform(aco.object.header.frame_id))
320 world_to_header_frame = tf->getTransform(aco.object.header.frame_id);
324 world_to_header_frame.setIdentity();
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());
331 object_pose = state.getGlobalLinkTransform(lm).inverse() * world_to_header_frame * object_pose;
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());
341 if (state.clearAttachedBody(aco.object.id))
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());
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());
355 RCLCPP_ERROR(LOGGER,
"The attached body for link '%s' has no geometry", aco.link_name.c_str());
357 else if (aco.object.operation == moveit_msgs::msg::CollisionObject::REMOVE)
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());
363 RCLCPP_ERROR(LOGGER,
"Unknown collision object operation: %d", aco.object.operation);
366 static bool _robotStateMsgToRobotStateHelper(
const Transforms* tf,
const moveit_msgs::msg::RobotState& robot_state,
367 RobotState& state,
bool copy_attached_bodies)
370 const moveit_msgs::msg::RobotState& rs = robot_state;
372 if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
374 RCLCPP_ERROR(LOGGER,
"Found empty JointState message");
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;
382 if (valid && copy_attached_bodies)
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);
403 bool result = _jointStateToRobotState(joint_state, state);
409 bool copy_attached_bodies)
411 bool result = _robotStateMsgToRobotStateHelper(
nullptr, robot_state, state, copy_attached_bodies);
417 bool copy_attached_bodies)
419 bool result = _robotStateMsgToRobotStateHelper(&tf, robot_state, state, copy_attached_bodies);
425 bool copy_attached_bodies)
427 robot_state.is_diff =
false;
429 _robotStateToMultiDOFJointState(state, robot_state.multi_dof_joint_state);
431 if (copy_attached_bodies)
433 std::vector<const AttachedBody*> attached_bodies;
440 const std::vector<const AttachedBody*>& attached_bodies,
441 std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objs)
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]);
450 const std::vector<const JointModel*>& js = state.
getRobotModel()->getSingleDOFJointModels();
451 joint_state = sensor_msgs::msg::JointState();
455 joint_state.name.push_back(joint_model->getName());
456 joint_state.position.push_back(state.
getVariablePosition(joint_model->getFirstVariableIndex()));
458 joint_state.velocity.push_back(state.
getVariableVelocity(joint_model->getFirstVariableIndex()));
462 if (joint_state.velocity.size() != joint_state.position.size())
463 joint_state.velocity.clear();
465 joint_state.header.frame_id = state.
getRobotModel()->getModelFrame();
471 if (trajectory.points.empty() || point_id > trajectory.points.size() - 1)
473 RCLCPP_ERROR(LOGGER,
"Invalid point_id");
476 if (trajectory.joint_names.empty())
478 RCLCPP_ERROR(LOGGER,
"No joint names specified");
483 if (!trajectory.points[point_id].velocities.empty())
485 if (!trajectory.points[point_id].accelerations.empty())
487 if (!trajectory.points[point_id].effort.empty())
488 state.
setVariableEffort(trajectory.joint_names, trajectory.points[point_id].effort);
522 const std::vector<std::string>& joint_groups_ordering,
bool include_header,
523 const std::string& separator)
525 std::stringstream headers;
526 std::stringstream joints;
528 for (
const std::string& joint_group_id : joint_groups_ordering)
542 std::vector<double> group_variable_positions;
548 joints << group_variable_positions[i] << separator;
554 out << headers.str() <<
'\n';
555 out << joints.str() <<
'\n';
560 std::stringstream line_stream(line);
567 if (!std::getline(line_stream, cell, separator[0]))
568 RCLCPP_ERROR(LOGGER,
"Missing variable %s", state.
getVariableNames()[i].c_str());
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....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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...
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...
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
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...
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.
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...
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.
const rclcpp::Logger LOGGER
Main namespace for MoveIt.
std::string append(const std::string &left, const std::string &right)