Go to the documentation of this file.
41 #include <moveit_msgs/RobotState.h>
64 bool copy_attached_bodies =
true);
74 bool copy_attached_bodies =
true);
83 bool copy_attached_bodies =
true);
91 const std::vector<const AttachedBody*>& attached_bodies,
92 std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs);
118 void robotStateToStream(
const RobotState& state, std::ostream& out,
bool include_header =
true,
119 const std::string& separator =
",");
131 const std::vector<std::string>& joint_groups_ordering,
bool include_header =
true,
132 const std::string& separator =
",");
141 void streamToRobotState(RobotState& state,
const std::string& line,
const std::string& separator =
",");
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.
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...
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.
void robotStateToJointStateMsg(const RobotState &state, sensor_msgs::JointState &joint_state)
Convert a MoveIt robot state to a joint state message.
Main namespace for MoveIt.
bool jointTrajPointToRobotState(const trajectory_msgs::JointTrajectory &trajectory, std::size_t point_id, RobotState &state)
Convert a joint trajectory point to a MoveIt robot state.
bool jointStateToRobotState(const sensor_msgs::JointState &joint_state, RobotState &state)
Convert a joint state to a MoveIt robot state.
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.
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.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14