moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <moveit/robot_state/robot_state.h>
#include <moveit/transforms/transforms.h>
#include <moveit_msgs/msg/robot_state.hpp>
Go to the source code of this file.
Namespaces | |
namespace | moveit |
Main namespace for MoveIt. | |
namespace | moveit::core |
Core components of MoveIt. | |
Functions | |
bool | moveit::core::jointStateToRobotState (const sensor_msgs::msg::JointState &joint_state, RobotState &state) |
Convert a joint state to a MoveIt robot state. | |
bool | moveit::core::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. | |
bool | moveit::core::robotStateMsgToRobotState (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. | |
void | moveit::core::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. | |
void | moveit::core::attachedBodiesToAttachedCollisionObjectMsgs (const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs) |
Convert AttachedBodies to AttachedCollisionObjects. | |
void | moveit::core::robotStateToJointStateMsg (const RobotState &state, sensor_msgs::msg::JointState &joint_state) |
Convert a MoveIt robot state to a joint state message. | |
bool | moveit::core::jointTrajPointToRobotState (const trajectory_msgs::msg::JointTrajectory &trajectory, std::size_t point_id, RobotState &state) |
Convert a joint trajectory point to a MoveIt robot state. | |
void | moveit::core::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 stream e.g. for file saving. | |
void | moveit::core::robotStateToStream (const RobotState &state, std::ostream &out, const std::vector< std::string > &joint_groups_ordering, 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 stream e.g. for file saving. This version can order by joint model groups. | |
void | moveit::core::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. | |