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>
62bool jointStateToRobotStateImpl(
const sensor_msgs::msg::JointState& joint_state, RobotState& state)
64 if (joint_state.name.size() != joint_state.position.size())
66 RCLCPP_ERROR(
getLogger(),
"Different number of names and positions in JointState message: %zu, %zu",
67 joint_state.name.size(), joint_state.position.size());
71 state.setVariableValues(joint_state);
76bool multiDofJointsToRobotState(
const sensor_msgs::msg::MultiDOFJointState& mjs, RobotState& state,
const Transforms* tf)
78 std::size_t nj = mjs.joint_names.size();
79 if (nj != mjs.transforms.size())
81 RCLCPP_ERROR(
getLogger(),
"Different number of names, values or frames in MultiDOFJointState message.");
86 Eigen::Isometry3d inv_t;
87 bool use_inv_t =
false;
96 const Eigen::Isometry3d& t2fixed_frame = tf->getTransform(mjs.header.frame_id);
99 inv_t = t2fixed_frame.inverse();
102 catch (std::exception& ex)
104 RCLCPP_ERROR(
getLogger(),
"Caught %s", ex.what());
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());
122 for (std::size_t i = 0; i < nj; ++i)
124 const std::string& joint_name = mjs.joint_names[i];
125 if (!state.getRobotModel()->hasJointModel(joint_name))
127 RCLCPP_WARN(
getLogger(),
"No joint matching multi-dof joint '%s'", joint_name.c_str());
131 Eigen::Isometry3d transf = tf2::transformToEigen(mjs.transforms[i]);
134 transf = transf * inv_t;
136 state.setJointPositions(joint_name, transf);
142void robotStateToMultiDofJointState(
const RobotState& state, sensor_msgs::msg::MultiDOFJointState& mjs)
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)
149 geometry_msgs::msg::TransformStamped p;
150 if (state.dirtyJointTransform(joint_model))
154 joint_model->computeTransform(state.getJointPositions(joint_model), t);
155 p = tf2::eigenToTransform(t);
158 p = tf2::eigenToTransform(state.getJointTransform(joint_model));
159 mjs.joint_names.push_back(joint_model->getName());
160 mjs.transforms.push_back(p.transform);
162 mjs.header.frame_id = state.getRobotModel()->getModelFrame();
165class ShapeVisitorAddToCollisionObject :
public boost::static_visitor<void>
168 ShapeVisitorAddToCollisionObject(moveit_msgs::msg::CollisionObject* obj) : boost::static_visitor<void>(), obj_(obj)
172 void addToObject(
const shapes::ShapeMsg& sm,
const geometry_msgs::msg::Pose& pose)
175 boost::apply_visitor(*
this, sm);
178 void operator()(
const shape_msgs::msg::Plane& shape_msg)
const
180 obj_->planes.push_back(shape_msg);
181 obj_->plane_poses.push_back(*pose_);
184 void operator()(
const shape_msgs::msg::Mesh& shape_msg)
const
186 obj_->meshes.push_back(shape_msg);
187 obj_->mesh_poses.push_back(*pose_);
190 void operator()(
const shape_msgs::msg::SolidPrimitive& shape_msg)
const
192 obj_->primitives.push_back(shape_msg);
193 obj_->primitive_poses.push_back(*pose_);
197 moveit_msgs::msg::CollisionObject* obj_;
198 const geometry_msgs::msg::Pose* pose_;
201void attachedBodyToMsg(
const AttachedBody& attached_body, moveit_msgs::msg::AttachedCollisionObject& aco)
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());
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)
226 if (shapes::constructMsgFromShape(ab_shapes[j].get(), sm))
228 geometry_msgs::msg::Pose p;
229 p = tf2::toMsg(shape_poses[j]);
230 sv.addToObject(sm, p);
233 aco.object.subframe_names.clear();
234 aco.object.subframe_poses.clear();
235 for (
const auto& frame_pair : attached_body.getSubframes())
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);
244void msgToAttachedBody(
const Transforms* tf,
const moveit_msgs::msg::AttachedCollisionObject& aco, RobotState& state)
246 if (aco.object.operation == moveit_msgs::msg::CollisionObject::ADD)
248 if (!aco.object.primitives.empty() || !aco.object.meshes.empty() || !aco.object.planes.empty())
250 if (aco.object.primitives.size() != aco.object.primitive_poses.size())
252 RCLCPP_ERROR(
getLogger(),
"Number of primitive shapes does not match "
253 "number of poses in collision object message");
257 if (aco.object.meshes.size() != aco.object.mesh_poses.size())
259 RCLCPP_ERROR(
getLogger(),
"Number of meshes does not match number of poses in collision object message");
263 if (aco.object.planes.size() != aco.object.plane_poses.size())
265 RCLCPP_ERROR(
getLogger(),
"Number of planes does not match number of poses in collision object message");
269 if (aco.object.subframe_poses.size() != aco.object.subframe_names.size())
271 RCLCPP_ERROR(
getLogger(),
"Number of subframe poses does not match number of subframe names in message");
275 const LinkModel* lm = state.getLinkModel(aco.link_name);
278 Eigen::Isometry3d object_pose;
279 tf2::fromMsg(aco.object.pose, object_pose);
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);
287 auto append = [&
shapes, &shape_poses](shapes::Shape* s,
const geometry_msgs::msg::Pose& pose_msg) {
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));
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]);
304 for (std::size_t i = 0; i < aco.object.subframe_poses.size(); ++i)
307 tf2::fromMsg(aco.object.subframe_poses[i], p);
308 std::string
name = aco.object.subframe_names[i];
309 subframe_poses[
name] = p;
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);
320 if (tf && tf->canTransform(aco.object.header.frame_id))
322 world_to_header_frame = tf->getTransform(aco.object.header.frame_id);
326 world_to_header_frame.setIdentity();
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());
333 object_pose = state.getGlobalLinkTransform(lm).inverse() * world_to_header_frame * object_pose;
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());
343 if (state.clearAttachedBody(aco.object.id))
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());
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());
357 RCLCPP_ERROR(
getLogger(),
"The attached body for link '%s' has no geometry", aco.link_name.c_str());
359 else if (aco.object.operation == moveit_msgs::msg::CollisionObject::REMOVE)
361 if (!state.clearAttachedBody(aco.object.id))
363 RCLCPP_ERROR(
getLogger(),
"The attached body '%s' can not be removed because it does not exist",
364 aco.link_name.c_str());
368 RCLCPP_ERROR(
getLogger(),
"Unknown collision object operation: %d", aco.object.operation);
371bool robotStateMsgToRobotStateHelper(
const Transforms* tf,
const moveit_msgs::msg::RobotState& robot_state,
372 RobotState& state,
bool copy_attached_bodies)
375 const moveit_msgs::msg::RobotState& rs = robot_state;
377 if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
379 RCLCPP_ERROR(
getLogger(),
"Found empty JointState message");
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;
387 if (valid && copy_attached_bodies)
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);
408 bool result = jointStateToRobotStateImpl(joint_state, state);
414 bool copy_attached_bodies)
416 bool result = robotStateMsgToRobotStateHelper(
nullptr, robot_state, state, copy_attached_bodies);
422 bool copy_attached_bodies)
424 bool result = robotStateMsgToRobotStateHelper(&tf, robot_state, state, copy_attached_bodies);
430 bool copy_attached_bodies)
432 robot_state.is_diff =
false;
434 robotStateToMultiDofJointState(state, robot_state.multi_dof_joint_state);
436 if (copy_attached_bodies)
438 std::vector<const AttachedBody*> attached_bodies;
445 const std::vector<const AttachedBody*>& attached_bodies,
446 std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objs)
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]);
455 const std::vector<const JointModel*>& js = state.
getRobotModel()->getSingleDOFJointModels();
456 joint_state = sensor_msgs::msg::JointState();
460 joint_state.name.push_back(joint_model->getName());
461 joint_state.position.push_back(state.
getVariablePosition(joint_model->getFirstVariableIndex()));
463 joint_state.velocity.push_back(state.
getVariableVelocity(joint_model->getFirstVariableIndex()));
467 if (joint_state.velocity.size() != joint_state.position.size())
468 joint_state.velocity.clear();
470 joint_state.header.frame_id = state.
getRobotModel()->getModelFrame();
476 if (trajectory.points.empty() || point_id > trajectory.points.size() - 1)
478 RCLCPP_ERROR(getLogger(),
"Invalid point_id");
481 if (trajectory.joint_names.empty())
483 RCLCPP_ERROR(getLogger(),
"No joint names specified");
488 if (!trajectory.points[point_id].velocities.empty())
490 if (!trajectory.points[point_id].accelerations.empty())
492 if (!trajectory.points[point_id].effort.empty())
493 state.
setVariableEffort(trajectory.joint_names, trajectory.points[point_id].effort);
527 const std::vector<std::string>& joint_groups_ordering,
bool include_header,
528 const std::string& separator)
530 std::stringstream headers;
531 std::stringstream joints;
533 for (
const std::string& joint_group_id : joint_groups_ordering)
547 std::vector<double> group_variable_positions;
553 joints << group_variable_positions[i] << separator;
559 out << headers.str() <<
'\n';
560 out << joints.str() <<
'\n';
565 std::stringstream line_stream(line);
572 if (!std::getline(line_stream, cell, separator[0]))
573 RCLCPP_ERROR(getLogger(),
"Missing variable %s", state.
getVariableNames()[i].c_str());
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.
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...
rclcpp::Logger getLogger()
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.
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
std::string append(const std::string &left, const std::string &right)