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())
59 ROS_ERROR_NAMED(LOGNAME,
"Different number of names and positions in JointState message: %zu, %zu",
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())
75 ROS_ERROR_NAMED(LOGNAME,
"Different number of names, values or frames in MultiDOFJointState message.");
80 Eigen::Affine3d inv_t;
81 bool use_inv_t =
false;
89 const Eigen::Affine3d& t2fixed_frame = tf->getTransform(mjs.header.frame_id);
92 inv_t = t2fixed_frame.inverse(Eigen::Isometry);
95 catch (std::exception& ex)
104 ROS_WARN_NAMED(LOGNAME,
"The transform for multi-dof joints was specified in frame '%s' " 105 "but it was not possible to transform that to frame '%s'",
106 mjs.header.frame_id.c_str(), state.getRobotModel()->getModelFrame().c_str());
109 for (std::size_t i = 0; i < nj; ++i)
111 const std::string& joint_name = mjs.joint_names[i];
112 if (!state.getRobotModel()->hasJointModel(joint_name))
114 ROS_WARN_NAMED(LOGNAME,
"No joint matching multi-dof joint '%s'", joint_name.c_str());
118 Eigen::Affine3d transf;
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 (std::size_t i = 0; i < js.size(); ++i)
137 geometry_msgs::Transform p;
138 if (state.dirtyJointTransform(js[i]))
142 js[i]->computeTransform(state.getJointPositions(js[i]), t);
147 mjs.joint_names.push_back(js[i]->
getName());
148 mjs.transforms.push_back(p);
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_;
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 (std::set<std::string>::const_iterator it = touch_links.begin(); it != touch_links.end(); ++it)
196 aco.touch_links.push_back(*it);
197 aco.object.header.frame_id = aco.link_name;
198 aco.object.id = attached_body.getName();
200 aco.object.operation = moveit_msgs::CollisionObject::ADD;
201 const std::vector<shapes::ShapeConstPtr>& ab_shapes = attached_body.getShapes();
203 ShapeVisitorAddToCollisionObject sv(&aco.object);
204 aco.object.primitives.clear();
205 aco.object.meshes.clear();
206 aco.object.planes.clear();
207 aco.object.primitive_poses.clear();
208 aco.object.mesh_poses.clear();
209 aco.object.plane_poses.clear();
210 for (std::size_t j = 0; j < ab_shapes.size(); ++j)
215 geometry_msgs::Pose p;
217 sv.addToObject(sm, p);
222 static void _msgToAttachedBody(
const Transforms* tf,
const moveit_msgs::AttachedCollisionObject& aco, RobotState& state)
224 if (aco.object.operation == moveit_msgs::CollisionObject::ADD)
226 if (!aco.object.primitives.empty() || !aco.object.meshes.empty() || !aco.object.planes.empty())
228 if (aco.object.primitives.size() != aco.object.primitive_poses.size())
231 "number of poses in collision object message");
235 if (aco.object.meshes.size() != aco.object.mesh_poses.size())
237 ROS_ERROR_NAMED(LOGNAME,
"Number of meshes does not match number of poses in collision object message");
241 if (aco.object.planes.size() != aco.object.plane_poses.size())
243 ROS_ERROR_NAMED(LOGNAME,
"Number of planes does not match number of poses in collision object message");
247 const LinkModel* lm = state.getLinkModel(aco.link_name);
250 std::vector<shapes::ShapeConstPtr>
shapes;
253 for (std::size_t i = 0; i < aco.object.primitives.size(); ++i)
264 for (std::size_t i = 0; i < aco.object.meshes.size(); ++i)
275 for (std::size_t i = 0; i < aco.object.planes.size(); ++i)
292 if (state.knowsFrameTransform(aco.object.header.frame_id))
293 t0 = state.getFrameTransform(aco.object.header.frame_id);
294 else if (tf && tf->canTransform(aco.object.header.frame_id))
295 t0 = tf->getTransform(aco.object.header.frame_id);
300 "The pose of the attached body may be incorrect",
301 aco.object.header.frame_id.c_str());
303 Eigen::Affine3d t = state.getGlobalLinkTransform(lm).inverse(Eigen::Isometry) * t0;
304 for (std::size_t i = 0; i < poses.size(); ++i)
305 poses[i] = t * poses[i];
309 ROS_ERROR_NAMED(LOGNAME,
"There is no geometry to attach to link '%s' as part of attached body '%s'",
310 aco.link_name.c_str(), aco.object.id.c_str());
313 if (state.clearAttachedBody(aco.object.id))
314 ROS_DEBUG_NAMED(LOGNAME,
"The robot state already had an object named '%s' attached to link '%s'. " 315 "The object was replaced.",
316 aco.object.id.c_str(), aco.link_name.c_str());
317 state.attachBody(aco.object.id, shapes, poses, aco.touch_links, aco.link_name, aco.detach_posture);
318 ROS_DEBUG_NAMED(LOGNAME,
"Attached object '%s' to link '%s'", aco.object.id.c_str(), aco.link_name.c_str());
323 ROS_ERROR_NAMED(LOGNAME,
"The attached body for link '%s' has no geometry", aco.link_name.c_str());
325 else if (aco.object.operation == moveit_msgs::CollisionObject::REMOVE)
327 if (!state.clearAttachedBody(aco.object.id))
328 ROS_ERROR_NAMED(LOGNAME,
"The attached body '%s' can not be removed because it does not exist",
329 aco.link_name.c_str());
332 ROS_ERROR_NAMED(LOGNAME,
"Unknown collision object operation: %d", aco.object.operation);
335 static bool _robotStateMsgToRobotStateHelper(
const Transforms* tf,
const moveit_msgs::RobotState&
robot_state,
336 RobotState& state,
bool copy_attached_bodies)
339 const moveit_msgs::RobotState& rs = robot_state;
341 if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
347 bool result1 = _jointStateToRobotState(robot_state.joint_state, state);
348 bool result2 = _multiDOFJointsToRobotState(robot_state.multi_dof_joint_state, state, tf);
349 valid = result1 || result2;
351 if (valid && copy_attached_bodies)
353 if (!robot_state.is_diff)
354 state.clearAttachedBodies();
355 for (std::size_t i = 0; i < robot_state.attached_collision_objects.size(); ++i)
356 _msgToAttachedBody(tf, robot_state.attached_collision_objects[i], state);
371 bool result = _jointStateToRobotState(joint_state, state);
378 bool result = _robotStateMsgToRobotStateHelper(
nullptr, robot_state, state, copy_attached_bodies);
384 bool copy_attached_bodies)
386 bool result = _robotStateMsgToRobotStateHelper(&tf, robot_state, state, copy_attached_bodies);
393 robot_state.is_diff =
false;
395 _robotStateToMultiDOFJointState(state, robot_state.multi_dof_joint_state);
397 if (copy_attached_bodies)
399 std::vector<const AttachedBody*> attached_bodies;
406 const std::vector<const AttachedBody*>& attached_bodies,
407 std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
409 attached_collision_objs.resize(attached_bodies.size());
410 for (std::size_t i = 0; i < attached_bodies.size(); ++i)
411 _attachedBodyToMsg(*attached_bodies[i], attached_collision_objs[i]);
416 const std::vector<const JointModel*>& js = state.
getRobotModel()->getSingleDOFJointModels();
417 joint_state = sensor_msgs::JointState();
419 for (std::size_t i = 0; i < js.size(); ++i)
421 joint_state.name.push_back(js[i]->
getName());
428 if (joint_state.velocity.size() != joint_state.position.size())
429 joint_state.velocity.clear();
431 joint_state.header.frame_id = state.
getRobotModel()->getModelFrame();
437 if (trajectory.points.empty() || point_id > trajectory.points.size() - 1)
442 if (trajectory.joint_names.empty())
449 if (!trajectory.points[point_id].velocities.empty())
451 if (!trajectory.points[point_id].accelerations.empty())
453 if (!trajectory.points[point_id].effort.empty())
454 state.
setVariableEffort(trajectory.joint_names, trajectory.points[point_id].effort);
488 const std::vector<std::string>& joint_groups_ordering,
bool include_header,
489 const std::string& separator)
491 std::stringstream headers;
492 std::stringstream joints;
494 for (std::size_t j = 0; j < joint_groups_ordering.size(); ++j)
508 std::vector<double> group_variable_positions;
514 joints << group_variable_positions[i] << separator;
520 out << headers.str() << std::endl;
521 out << joints.str() << std::endl;
526 std::stringstream lineStream(line);
533 if (!std::getline(lineStream, cell, separator[0]))
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
Core components of MoveIt!
void attachedBodiesToAttachedCollisionObjectMsgs(const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objs)
Convert AttachedBodies to AttachedCollisionObjects.
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...
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
#define ROS_WARN_NAMED(name,...)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
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 ...
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
bool jointTrajPointToRobotState(const trajectory_msgs::JointTrajectory &trajectory, std::size_t point_id, RobotState &state)
Convert a joint trajectory point to a MoveIt! robot state.
std::string getName(void *handle)
void robotStateToJointStateMsg(const RobotState &state, sensor_msgs::JointState &joint_state)
Convert a MoveIt! robot state to a joint state message.
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully. If you change these values externally you need to make sure you trigger a forced update for the state by calling update(true).
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in 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...
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
#define ROS_DEBUG_NAMED(name,...)
void update(bool force=false)
Update all transforms.
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt! robot state...
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
const std::string LOGNAME
const geometry_msgs::Pose * pose_
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt! robot state to a robot state message.
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
bool jointStateToRobotState(const sensor_msgs::JointState &joint_state, RobotState &state)
Convert a joint state to a MoveIt! robot state.
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
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 setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort 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...
Main namespace for MoveIt!
moveit_msgs::CollisionObject * obj_
std::size_t getVariableCount() const
Get the number of variables that make up this state.
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 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.
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
std::shared_ptr< const Shape > ShapeConstPtr