Core components of MoveIt! More...
Classes | |
class | AttachedBody |
Object defining bodies that can be attached to robot links. This is useful when handling objects picked up by the robot. More... | |
class | FixedJointModel |
A fixed joint. More... | |
class | FloatingJointModel |
A floating joint. More... | |
class | JointModel |
A joint from the robot. Models the transform that this joint applies in the kinematic chain. A joint consists of multiple variables. In the simplest case, when the joint is a single DOF, there is only one variable and its name is the same as the joint's name. For multi-DOF joints, each variable has a local name (e.g., x, y) but the full variable name as seen from the outside of this class is a concatenation of the "joint name"/"local
name" (e.g., a joint named 'base' with local variables 'x' and 'y' will store its full variable names as 'base/x' and 'base/y'). Local names are never used to reference variables directly. More... | |
class | JointModelGroup |
class | LinkModel |
A link from the robot. Contains the constant transform applied to the link and its geometry. More... | |
class | PlanarJointModel |
A planar joint. More... | |
class | PrismaticJointModel |
A prismatic joint. More... | |
class | RevoluteJointModel |
A revolute joint. More... | |
class | RobotModel |
Definition of a kinematic model. This class is not thread safe, however multiple instances can be created. More... | |
class | RobotState |
Representation of a robot's state. This includes position, velocity, acceleration and effort. More... | |
class | Transforms |
Provides an implementation of a snapshot of a transform tree that can be easily queried for transforming different quantities. Transforms are maintained as a list of transforms to a particular frame. All stored transforms are considered fixed. More... | |
struct | VariableBounds |
Typedefs | |
typedef boost::function< void(AttachedBody *body, bool attached) | AttachedBodyCallback ) |
typedef std::map< std::string, Eigen::Affine3d, std::less < std::string > , Eigen::aligned_allocator < std::pair< const std::string, Eigen::Affine3d > > > | FixedTransformsMap |
Map frame names to the transformation matrix that can transform objects from the frame name to the planning frame. | |
typedef boost::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values) | GroupStateValidityCallbackFn ) |
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_group_variable_values the state is valid or not. Returns true if the state is valid. This call is allowed to modify robot_state (e.g., set joint_group_variable_values) | |
typedef std::vector< const JointModel::Bounds * > | JointBoundsVector |
typedef std::map< std::string, JointModelGroup * > | JointModelGroupMap |
Map of names to instances for JointModelGroup. | |
typedef std::map< std::string, const JointModelGroup * > | JointModelGroupMapConst |
Map of names to const instances for JointModelGroup. | |
typedef std::map< std::string, JointModel * > | JointModelMap |
Map of names to instances for JointModel. | |
typedef std::map< std::string, const JointModel * > | JointModelMapConst |
Map of names to const instances for JointModel. | |
typedef std::map< std::string, LinkModel * > | LinkModelMap |
Map of names to instances for LinkModel. | |
typedef std::map< std::string, const LinkModel * > | LinkModelMapConst |
Map of names to const instances for LinkModel. | |
typedef std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * > , Eigen::aligned_allocator < std::pair< const LinkModel *, Eigen::Affine3d > > > | LinkTransformMap |
Map from link model instances to Eigen transforms. | |
typedef boost::function < kinematics::KinematicsBasePtr(const JointModelGroup *) | SolverAllocatorFn ) |
Function type that allocates a kinematics solver for a particular group. | |
typedef std::map< const JointModelGroup *, SolverAllocatorFn > | SolverAllocatorMapFn |
Map from group instances to allocator functions & bijections. | |
typedef std::map< std::string, VariableBounds > | VariableBoundsMap |
Data type for holding mappings from variable names to their bounds. | |
typedef std::map< std::string, int > | VariableIndexMap |
Data type for holding mappings from variable names to their position in a state vector. | |
Functions | |
bool | jointStateToRobotState (const sensor_msgs::JointState &joint_state, RobotState &state) |
Convert a joint state to a MoveIt! robot state. | |
bool | jointTrajPointToRobotState (const trajectory_msgs::JointTrajectory &trajectory, std::size_t point_id, RobotState &state) |
Convert a joint trajectory point to a MoveIt! robot state. | |
MOVEIT_CLASS_FORWARD (Transforms) | |
MOVEIT_CLASS_FORWARD (RobotState) | |
MOVEIT_CLASS_FORWARD (RobotModel) | |
std::ostream & | operator<< (std::ostream &out, const VariableBounds &b) |
Operator overload for printing variable bounds to a stream. | |
std::ostream & | operator<< (std::ostream &out, const RobotState &s) |
Operator overload for printing variable bounds to a stream. | |
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. | |
bool | 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. | |
void | robotStateToJointStateMsg (const RobotState &state, sensor_msgs::JointState &joint_state) |
Convert a MoveIt! robot state to a joint state message. | |
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. | |
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 stream e.g. for file saving. | |
void | 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 | 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. |
Core components of MoveIt!
typedef boost::function<void(AttachedBody* body, bool attached) moveit::core::AttachedBodyCallback) |
Definition at line 50 of file attached_body.h.
typedef std::map<std::string, Eigen::Affine3d, std::less<std::string>, Eigen::aligned_allocator<std::pair<const std::string, Eigen::Affine3d> > > moveit::core::FixedTransformsMap |
Map frame names to the transformation matrix that can transform objects from the frame name to the planning frame.
Definition at line 56 of file transforms.h.
typedef boost::function<bool(RobotState* robot_state, const JointModelGroup* joint_group, const double* joint_group_variable_values) moveit::core::GroupStateValidityCallbackFn) |
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_group_variable_values the state is valid or not. Returns true if the state is valid. This call is allowed to modify robot_state (e.g., set joint_group_variable_values)
Definition at line 63 of file robot_state.h.
typedef std::vector<const JointModel::Bounds*> moveit::core::JointBoundsVector |
Definition at line 67 of file joint_model_group.h.
typedef std::map<std::string, JointModelGroup*> moveit::core::JointModelGroupMap |
Map of names to instances for JointModelGroup.
Definition at line 62 of file joint_model_group.h.
typedef std::map<std::string, const JointModelGroup*> moveit::core::JointModelGroupMapConst |
Map of names to const instances for JointModelGroup.
Definition at line 65 of file joint_model_group.h.
typedef std::map<std::string, JointModel*> moveit::core::JointModelMap |
Map of names to instances for JointModel.
Definition at line 91 of file joint_model.h.
typedef std::map<std::string, const JointModel*> moveit::core::JointModelMapConst |
Map of names to const instances for JointModel.
Definition at line 94 of file joint_model.h.
typedef std::map<std::string, LinkModel*> moveit::core::LinkModelMap |
Map of names to instances for LinkModel.
Definition at line 53 of file link_model.h.
typedef std::map<std::string, const LinkModel*> moveit::core::LinkModelMapConst |
Map of names to const instances for LinkModel.
Definition at line 59 of file link_model.h.
typedef std::map<const LinkModel*, Eigen::Affine3d, std::less<const LinkModel*>, Eigen::aligned_allocator<std::pair<const LinkModel*, Eigen::Affine3d> > > moveit::core::LinkTransformMap |
Map from link model instances to Eigen transforms.
Definition at line 64 of file link_model.h.
typedef boost::function<kinematics::KinematicsBasePtr(const JointModelGroup*) moveit::core::SolverAllocatorFn) |
Function type that allocates a kinematics solver for a particular group.
Definition at line 53 of file joint_model_group.h.
typedef std::map<const JointModelGroup*, SolverAllocatorFn> moveit::core::SolverAllocatorMapFn |
Map from group instances to allocator functions & bijections.
Definition at line 59 of file joint_model_group.h.
typedef std::map<std::string, VariableBounds> moveit::core::VariableBoundsMap |
Data type for holding mappings from variable names to their bounds.
Definition at line 88 of file joint_model.h.
typedef std::map<std::string, int> moveit::core::VariableIndexMap |
Data type for holding mappings from variable names to their position in a state vector.
Definition at line 82 of file joint_model.h.
bool moveit::core::jointStateToRobotState | ( | const sensor_msgs::JointState & | joint_state, |
RobotState & | state | ||
) |
Convert a joint state to a MoveIt! robot state.
joint_state | The input joint state to be converted |
state | The resultant MoveIt! robot state |
Definition at line 354 of file conversions.cpp.
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.
joint_trajectory | The input msg |
point_id | The index of the trajectory point in the joint trajectory. |
state | The resultant MoveIt! robot state |
Definition at line 413 of file conversions.cpp.
moveit::core::MOVEIT_CLASS_FORWARD | ( | Transforms | ) |
moveit::core::MOVEIT_CLASS_FORWARD | ( | RobotState | ) |
moveit::core::MOVEIT_CLASS_FORWARD | ( | RobotModel | ) |
std::ostream & moveit::core::operator<< | ( | std::ostream & | out, |
const VariableBounds & | b | ||
) |
Operator overload for printing variable bounds to a stream.
Definition at line 215 of file joint_model.cpp.
std::ostream & moveit::core::operator<< | ( | std::ostream & | out, |
const RobotState & | s | ||
) |
Operator overload for printing variable bounds to a stream.
Definition at line 2206 of file robot_state.cpp.
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.
tf | An instance of a transforms object |
robot_state | The input robot state msg |
state | The resultant MoveIt! robot state |
copy_attached_bodies | Flag to include attached objects in robot state copy |
Definition at line 369 of file conversions.cpp.
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.
robot_state | The input robot state msg |
state | The resultant MoveIt! robot state |
copy_attached_bodies | Flag to include attached objects in robot state copy |
Definition at line 361 of file conversions.cpp.
void moveit::core::robotStateToJointStateMsg | ( | const RobotState & | state, |
sensor_msgs::JointState & | joint_state | ||
) |
Convert a MoveIt! robot state to a joint state message.
state | The input MoveIt! robot state object |
robot_state | The resultant JointState message |
Definition at line 393 of file conversions.cpp.
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.
state | The input MoveIt! robot state object |
robot_state | The resultant RobotState *message |
copy_attached_bodies | Flag to include attached objects in robot state copy |
Definition at line 377 of file conversions.cpp.
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.
state | - The input MoveIt! robot state object |
out | - a file stream, or any other stream |
include_header | - flag to prefix the output with a line of joint names. |
separator | - allows to override the comma seperator with any symbol, such as a white space |
Definition at line 438 of file conversions.cpp.
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.
state | - The input MoveIt! robot state object |
out | - a file stream, or any other stream |
joint_group_ordering | - output joints based on ordering of joint groups |
include_header | - flag to prefix the output with a line of joint names. |
separator | - allows to override the comma seperator with any symbol, such as a white space |
Definition at line 467 of file conversions.cpp.
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.
state | - the output MoveIt! robot state object |
line | - the input string of joint values |
separator | - allows to override the comma seperator with any symbol, such as a white space |
Definition at line 504 of file conversions.cpp.