Namespaces | Functions
conversions.cpp File Reference
#include <moveit/robot_state/conversions.h>
#include <geometric_shapes/shape_operations.h>
#include <eigen_conversions/eigen_msg.h>
#include <boost/lexical_cast.hpp>
Include dependency graph for conversions.cpp:

Go to the source code of this file.

Namespaces

 moveit
 Main namespace for MoveIt!
 
 moveit::core
 Core components of MoveIt!
 

Functions

void moveit::core::attachedBodiesToAttachedCollisionObjectMsgs (const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objs)
 Convert AttachedBodies to AttachedCollisionObjects. More...
 
bool moveit::core::jointStateToRobotState (const sensor_msgs::JointState &joint_state, RobotState &state)
 Convert a joint state to a MoveIt! robot state. More...
 
bool moveit::core::jointTrajPointToRobotState (const trajectory_msgs::JointTrajectory &trajectory, std::size_t point_id, RobotState &state)
 Convert a joint trajectory point to a MoveIt! robot state. More...
 
bool moveit::core::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. More...
 
bool moveit::core::robotStateMsgToRobotState (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. More...
 
void moveit::core::robotStateToJointStateMsg (const RobotState &state, sensor_msgs::JointState &joint_state)
 Convert a MoveIt! robot state to a joint state message. More...
 
void moveit::core::robotStateToRobotStateMsg (const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
 Convert a MoveIt! robot state to a robot state message. More...
 
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. More...
 
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. More...
 
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. More...
 

Variable Documentation

moveit_msgs::CollisionObject* obj_
private

Definition at line 185 of file conversions.cpp.

const geometry_msgs::Pose* pose_
private

Definition at line 186 of file conversions.cpp.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33