41 #include <boost/lexical_cast.hpp>
47 const std::string
LOGNAME =
"robot_state";
55 static bool _jointStateToRobotState(
const sensor_msgs::JointState& joint_state, RobotState& state)
57 if (joint_state.name.size() != joint_state.position.size())
60 joint_state.name.size(), joint_state.position.size());
64 state.setVariableValues(joint_state);
69 static bool _multiDOFJointsToRobotState(
const sensor_msgs::MultiDOFJointState& mjs, RobotState& state,
72 std::size_t nj = mjs.joint_names.size();
73 if (nj != mjs.transforms.size())
80 Eigen::Isometry3d inv_t;
81 bool use_inv_t =
false;
89 const Eigen::Isometry3d& t2fixed_frame = tf->getTransform(mjs.header.frame_id);
92 inv_t = t2fixed_frame.inverse();
95 catch (std::exception& ex)
105 "The transform for multi-dof joints was specified in frame '%s' "
106 "but it was not possible to transform that to frame '%s'",
107 mjs.header.frame_id.c_str(), state.getRobotModel()->getModelFrame().c_str());
110 for (std::size_t i = 0; i < nj; ++i)
112 const std::string& joint_name = mjs.joint_names[i];
113 if (!state.getRobotModel()->hasJointModel(joint_name))
122 transf = transf * inv_t;
124 state.setJointPositions(joint_name, transf);
130 static inline void _robotStateToMultiDOFJointState(
const RobotState& state, sensor_msgs::MultiDOFJointState& mjs)
132 const std::vector<const JointModel*>& js = state.getRobotModel()->getMultiDOFJointModels();
133 mjs.joint_names.clear();
134 mjs.transforms.clear();
135 for (
const JointModel* joint_model : js)
137 geometry_msgs::TransformStamped p;
138 if (state.dirtyJointTransform(joint_model))
142 joint_model->computeTransform(state.getJointPositions(joint_model), t);
147 mjs.joint_names.push_back(joint_model->getName());
148 mjs.transforms.push_back(p.transform);
150 mjs.header.frame_id = state.getRobotModel()->getModelFrame();
153 class ShapeVisitorAddToCollisionObject :
public boost::static_visitor<void>
156 ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) :
boost::static_visitor<void>(),
obj_(
obj)
160 void addToObject(
const shapes::ShapeMsg& sm,
const geometry_msgs::Pose& pose)
163 boost::apply_visitor(*
this, sm);
166 void operator()(
const shape_msgs::Plane& shape_msg)
const
168 obj_->planes.push_back(shape_msg);
172 void operator()(
const shape_msgs::Mesh& shape_msg)
const
174 obj_->meshes.push_back(shape_msg);
178 void operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
180 obj_->primitives.push_back(shape_msg);
185 moveit_msgs::CollisionObject*
obj_;
186 const geometry_msgs::Pose*
pose_;
189 static void _attachedBodyToMsg(
const AttachedBody& attached_body, moveit_msgs::AttachedCollisionObject& aco)
191 aco.link_name = attached_body.getAttachedLinkName();
192 aco.detach_posture = attached_body.getDetachPosture();
193 const std::set<std::string>& touch_links = attached_body.getTouchLinks();
194 aco.touch_links.clear();
195 for (
const std::string& touch_link : touch_links)
196 aco.touch_links.push_back(touch_link);
197 aco.object.header.frame_id = aco.link_name;
198 aco.object.id = attached_body.getName();
199 aco.object.pose =
tf2::toMsg(attached_body.getPose());
201 aco.object.operation = moveit_msgs::CollisionObject::ADD;
202 const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body.getShapes();
204 ShapeVisitorAddToCollisionObject sv(&aco.object);
205 aco.object.primitives.clear();
206 aco.object.meshes.clear();
207 aco.object.planes.clear();
208 aco.object.primitive_poses.clear();
209 aco.object.mesh_poses.clear();
210 aco.object.plane_poses.clear();
211 for (std::size_t j = 0; j < ab_shapes.size(); ++j)
216 geometry_msgs::Pose p;
218 sv.addToObject(sm, p);
221 aco.object.subframe_names.clear();
222 aco.object.subframe_poses.clear();
223 for (
const auto& frame_pair : attached_body.getSubframes())
225 aco.object.subframe_names.push_back(frame_pair.first);
226 geometry_msgs::Pose pose;
228 aco.object.subframe_poses.push_back(pose);
232 static void _msgToAttachedBody(
const Transforms* tf,
const moveit_msgs::AttachedCollisionObject& aco, RobotState& state)
234 if (aco.object.operation == moveit_msgs::CollisionObject::ADD)
236 if (!aco.object.primitives.empty() || !aco.object.meshes.empty() || !aco.object.planes.empty())
238 if (aco.object.primitives.size() != aco.object.primitive_poses.size())
241 "number of poses in collision object message");
245 if (aco.object.meshes.size() != aco.object.mesh_poses.size())
251 if (aco.object.planes.size() != aco.object.plane_poses.size())
257 if (aco.object.subframe_poses.size() != aco.object.subframe_names.size())
263 const LinkModel* lm = state.getLinkModel(aco.link_name);
266 Eigen::Isometry3d object_pose;
269 std::vector<shapes::ShapeConstPtr>
shapes;
271 const auto num_shapes = aco.object.primitives.size() + aco.object.meshes.size() + aco.object.planes.size();
272 shapes.reserve(num_shapes);
273 shape_poses.reserve(num_shapes);
278 Eigen::Isometry3d pose;
281 shape_poses.emplace_back(std::move(pose));
284 for (std::size_t i = 0; i < aco.object.primitives.size(); ++i)
286 for (std::size_t i = 0; i < aco.object.meshes.size(); ++i)
288 for (std::size_t i = 0; i < aco.object.planes.size(); ++i)
292 for (std::size_t i = 0; i < aco.object.subframe_poses.size(); ++i)
296 std::string
name = aco.object.subframe_names[i];
297 subframe_poses[
name] = p;
303 bool frame_found =
false;
304 Eigen::Isometry3d world_to_header_frame;
305 world_to_header_frame = state.getFrameTransform(aco.object.header.frame_id, &frame_found);
308 if (tf && tf->canTransform(aco.object.header.frame_id))
309 world_to_header_frame = tf->getTransform(aco.object.header.frame_id);
312 world_to_header_frame.setIdentity();
314 "Cannot properly transform from frame '%s'. "
315 "The pose of the attached body may be incorrect",
316 aco.object.header.frame_id.c_str());
319 object_pose = state.getGlobalLinkTransform(lm).inverse() * world_to_header_frame * object_pose;
324 aco.link_name.c_str(), aco.object.id.c_str());
327 if (state.clearAttachedBody(aco.object.id))
329 "The robot state already had an object named '%s' attached to link '%s'. "
330 "The object was replaced.",
331 aco.object.id.c_str(), aco.link_name.c_str());
332 state.attachBody(aco.object.id, object_pose,
shapes, shape_poses, aco.touch_links, aco.link_name,
333 aco.detach_posture, subframe_poses);
334 ROS_DEBUG_NAMED(
LOGNAME,
"Attached object '%s' to link '%s'", aco.object.id.c_str(), aco.link_name.c_str());
341 else if (aco.object.operation == moveit_msgs::CollisionObject::REMOVE)
343 if (!state.clearAttachedBody(aco.object.id))
345 aco.link_name.c_str());
351 static bool _robotStateMsgToRobotStateHelper(
const Transforms* tf,
const moveit_msgs::RobotState&
robot_state,
352 RobotState& state,
bool copy_attached_bodies)
357 if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
363 bool result1 = _jointStateToRobotState(
robot_state.joint_state, state);
364 bool result2 = _multiDOFJointsToRobotState(
robot_state.multi_dof_joint_state, state, tf);
365 valid = result1 || result2;
367 if (valid && copy_attached_bodies)
370 state.clearAttachedBodies();
371 for (
const moveit_msgs::AttachedCollisionObject& attached_collision_object :
robot_state.attached_collision_objects)
372 _msgToAttachedBody(tf, attached_collision_object, state);
387 bool result = _jointStateToRobotState(joint_state, state);
394 bool result = _robotStateMsgToRobotStateHelper(
nullptr,
robot_state, state, copy_attached_bodies);
400 bool copy_attached_bodies)
402 bool result = _robotStateMsgToRobotStateHelper(&tf,
robot_state, state, copy_attached_bodies);
411 _robotStateToMultiDOFJointState(state,
robot_state.multi_dof_joint_state);
413 if (copy_attached_bodies)
415 std::vector<const AttachedBody*> attached_bodies;
416 state.getAttachedBodies(attached_bodies);
422 const std::vector<const AttachedBody*>& attached_bodies,
423 std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
425 attached_collision_objs.resize(attached_bodies.size());
426 for (std::size_t i = 0; i < attached_bodies.size(); ++i)
427 _attachedBodyToMsg(*attached_bodies[i], attached_collision_objs[i]);
432 const std::vector<const JointModel*>& js = state.getRobotModel()->getSingleDOFJointModels();
433 joint_state = sensor_msgs::JointState();
435 for (
const JointModel* joint_model : js)
437 joint_state.name.push_back(joint_model->getName());
438 joint_state.position.push_back(state.getVariablePosition(joint_model->getFirstVariableIndex()));
439 if (state.hasVelocities())
440 joint_state.velocity.push_back(state.getVariableVelocity(joint_model->getFirstVariableIndex()));
444 if (joint_state.velocity.size() != joint_state.position.size())
445 joint_state.velocity.clear();
447 joint_state.header.frame_id = state.getRobotModel()->getModelFrame();
453 if (trajectory.points.empty() || point_id > trajectory.points.size() - 1)
458 if (trajectory.joint_names.empty())
465 if (!trajectory.points[point_id].velocities.empty())
467 if (!trajectory.points[point_id].accelerations.empty())
469 if (!trajectory.points[point_id].effort.empty())
470 state.
setVariableEffort(trajectory.joint_names, trajectory.points[point_id].effort);
475 void robotStateToStream(
const RobotState& state, std::ostream& out,
bool include_header,
const std::string& separator)
480 for (std::size_t i = 0; i < state.getVariableCount(); ++i)
482 out << state.getVariableNames()[i];
485 if (i < state.getVariableCount() - 1)
492 for (std::size_t i = 0; i < state.getVariableCount(); ++i)
494 out << state.getVariablePositions()[i];
497 if (i < state.getVariableCount() - 1)
504 const std::vector<std::string>& joint_groups_ordering,
bool include_header,
505 const std::string& separator)
507 std::stringstream headers;
508 std::stringstream joints;
510 for (
const std::string& joint_group_id : joint_groups_ordering)
512 const JointModelGroup* jmg = state.getRobotModel()->getJointModelGroup(joint_group_id);
517 for (std::size_t i = 0; i < jmg->getVariableCount(); ++i)
519 headers << jmg->getVariableNames()[i] << separator;
524 std::vector<double> group_variable_positions;
525 state.copyJointGroupPositions(jmg, group_variable_positions);
528 for (std::size_t i = 0; i < jmg->getVariableCount(); ++i)
530 joints << group_variable_positions[i] << separator;
536 out << headers.str() << std::endl;
537 out << joints.str() << std::endl;
540 void streamToRobotState(RobotState& state,
const std::string& line,
const std::string& separator)
542 std::stringstream line_stream(line);
546 for (std::size_t i = 0; i < state.getVariableCount(); ++i)
549 if (!std::getline(line_stream, cell, separator[0]))
552 state.getVariablePositions()[i] = boost::lexical_cast<double>(cell.c_str());