moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Typedefs | Functions
moveit::core Namespace Reference

Core components of MoveIt. More...

Classes

class  AABB
 Represents an axis-aligned bounding box. More...
 
class  FixedJointModel
 A fixed joint. More...
 
class  FloatingJointModel
 A floating joint. More...
 
struct  VariableBounds
 
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  AttachedBody
 Object defining bodies that can be attached to robot links. More...
 
struct  JumpThreshold
 Struct with options for defining joint-space jump thresholds. More...
 
struct  MaxEEFStep
 Struct for containing max_step for computeCartesianPath. More...
 
class  CartesianInterpolator
 
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...
 
class  MoveItErrorCode
 a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from a function More...
 
class  RobotModelBuilder
 Easily build different robot models for testing. Essentially a programmer-friendly light wrapper around URDF and SRDF. Best shown by an example: More...
 

Typedefs

typedef std::map< std::string, size_t > VariableIndexMap
 Data type for holding mappings from variable names to their position in a state vector. More...
 
using VariableBoundsMap = std::map< std::string, VariableBounds >
 Data type for holding mappings from variable names to their bounds. More...
 
using JointModelMap = std::map< std::string, JointModel * >
 Map of names to instances for JointModel. More...
 
using JointModelMapConst = std::map< std::string, const JointModel * >
 Map of names to const instances for JointModel. More...
 
typedef std::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
 Function type that allocates a kinematics solver for a particular group. More...
 
using SolverAllocatorMapFn = std::map< const JointModelGroup *, SolverAllocatorFn >
 Map from group instances to allocator functions & bijections. More...
 
using JointModelGroupMap = std::map< std::string, JointModelGroup * >
 Map of names to instances for JointModelGroup. More...
 
using JointModelGroupMapConst = std::map< std::string, const JointModelGroup * >
 Map of names to const instances for JointModelGroup. More...
 
using JointBoundsVector = std::vector< const JointModel::Bounds * >
 
typedef std::map< std::string, LinkModel * > LinkModelMap
 Map of names to instances for LinkModel. More...
 
using LinkModelMapConst = std::map< std::string, const LinkModel * >
 Map of names to const instances for LinkModel. More...
 
using LinkTransformMap = std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > >
 Map from link model instances to Eigen transforms. More...
 
typedef std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
 
typedef std::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) More...
 
using FixedTransformsMap = std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > >
 Map frame names to the transformation matrix that can transform objects from the frame name to the planning frame. More...
 

Functions

 MOVEIT_CLASS_FORWARD (JointModelGroup)
 
 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. More...
 
void computeTurnDriveTurnGeometry (const double *from, const double *to, const double min_translational_distance, double &dx, double &dy, double &initial_turn, double &drive_angle, double &final_turn)
 Compute the geometry to turn toward the target point, drive straight and then turn to target orientation. More...
 
std::optional< int > hasJointSpaceJump (const std::vector< moveit::core::RobotStatePtr > &waypoints, const moveit::core::JointModelGroup &group, const moveit::core::JumpThreshold &jump_threshold)
 Checks if a joint-space path has a jump larger than the given threshold. More...
 
bool jointStateToRobotState (const sensor_msgs::msg::JointState &joint_state, RobotState &state)
 Convert a joint state to a MoveIt robot state. More...
 
bool 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. More...
 
bool 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. More...
 
void 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. More...
 
void attachedBodiesToAttachedCollisionObjectMsgs (const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs)
 Convert AttachedBodies to AttachedCollisionObjects. More...
 
void robotStateToJointStateMsg (const RobotState &state, sensor_msgs::msg::JointState &joint_state)
 Convert a MoveIt robot state to a joint state message. More...
 
bool jointTrajPointToRobotState (const trajectory_msgs::msg::JointTrajectory &trajectory, std::size_t point_id, RobotState &state)
 Convert a joint trajectory point to a MoveIt robot state. More...
 
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. More...
 
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. More...
 
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. More...
 
std::ostream & operator<< (std::ostream &out, const RobotState &s)
 Operator overload for printing variable bounds to a stream. More...
 
 MOVEIT_CLASS_FORWARD (Transforms)
 
std::string toString (double d)
 Convert a double to std::string using the classic C locale. More...
 
std::string toString (float f)
 Convert a float to std::string using the classic C locale. More...
 
double toDouble (const std::string &s)
 Converts a std::string to double using the classic C locale. More...
 
float toFloat (const std::string &s)
 Converts a std::string to float using the classic C locale. More...
 
bool isEmpty (const moveit_msgs::msg::PlanningScene &msg)
 Check if a message includes any information about a planning scene, or whether it is empty. More...
 
bool isEmpty (const moveit_msgs::msg::PlanningSceneWorld &msg)
 Check if a message includes any information about a planning scene world, or whether it is empty. More...
 
bool isEmpty (const moveit_msgs::msg::RobotState &msg)
 Check if a message includes any information about a robot state, or whether it is empty. More...
 
bool isEmpty (const moveit_msgs::msg::Constraints &msg)
 Check if a message specifies constraints. More...
 
bool isEmpty (const geometry_msgs::msg::Quaternion &msg)
 Check if the message contains any non-zero entries. More...
 
bool isEmpty (const geometry_msgs::msg::Pose &msg)
 Check if the message contains any non-zero entries. More...
 
std::string errorCodeToString (const MoveItErrorCode &error_code)
 Convenience function to translated error message into string. More...
 
moveit::core::RobotModelPtr loadTestingRobotModel (const std::string &robot_name)
 Loads a robot from moveit_resources. More...
 
urdf::ModelInterfaceSharedPtr loadModelInterface (const std::string &robot_name)
 Loads a URDF Model Interface from moveit_resources. More...
 
srdf::ModelSharedPtr loadSRDFModel (const std::string &robot_name)
 Loads an SRDF Model from moveit_resources. More...
 
void loadIKPluginForGroup (const rclcpp::Node::SharedPtr &node, JointModelGroup *jmg, const std::string &base_link, const std::string &tip_link, std::string plugin="KDL", double timeout=0.1)
 Load an IK solver plugin for the given joint model group. More...
 
template<class InType >
std::string toStringImpl (InType t)
 
template<class OutType >
OutType toRealImpl (const std::string &s)
 

Detailed Description

Core components of MoveIt.

Typedef Documentation

◆ AttachedBodyCallback

typedef std::function<void(AttachedBody* body, bool attached)> moveit::core::AttachedBodyCallback

Definition at line 52 of file attached_body.h.

◆ FixedTransformsMap

using moveit::core::FixedTransformsMap = typedef std::map<std::string, Eigen::Isometry3d, std::less<std::string>, Eigen::aligned_allocator<std::pair<const std::string, Eigen::Isometry3d> > >

Map frame names to the transformation matrix that can transform objects from the frame name to the planning frame.

Definition at line 52 of file transforms.h.

◆ GroupStateValidityCallbackFn

typedef std::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 70 of file robot_state.h.

◆ JointBoundsVector

using moveit::core::JointBoundsVector = typedef std::vector<const JointModel::Bounds*>

Definition at line 67 of file joint_model_group.h.

◆ JointModelGroupMap

using moveit::core::JointModelGroupMap = typedef std::map<std::string, JointModelGroup*>

Map of names to instances for JointModelGroup.

Definition at line 62 of file joint_model_group.h.

◆ JointModelGroupMapConst

using moveit::core::JointModelGroupMapConst = typedef std::map<std::string, const JointModelGroup*>

Map of names to const instances for JointModelGroup.

Definition at line 65 of file joint_model_group.h.

◆ JointModelMap

using moveit::core::JointModelMap = typedef std::map<std::string, JointModel*>

Map of names to instances for JointModel.

Definition at line 99 of file joint_model.h.

◆ JointModelMapConst

using moveit::core::JointModelMapConst = typedef std::map<std::string, const JointModel*>

Map of names to const instances for JointModel.

Definition at line 102 of file joint_model.h.

◆ LinkModelMap

typedef std::map<std::string, LinkModel*> moveit::core::LinkModelMap

Map of names to instances for LinkModel.

Definition at line 61 of file link_model.h.

◆ LinkModelMapConst

using moveit::core::LinkModelMapConst = typedef std::map<std::string, const LinkModel*>

Map of names to const instances for LinkModel.

Definition at line 64 of file link_model.h.

◆ LinkTransformMap

using moveit::core::LinkTransformMap = typedef std::map<const LinkModel*, Eigen::Isometry3d, std::less<const LinkModel*>, Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Isometry3d> > >

Map from link model instances to Eigen transforms.

Definition at line 67 of file link_model.h.

◆ SolverAllocatorFn

typedef std::function<kinematics::KinematicsBasePtr(const JointModelGroup*)> moveit::core::SolverAllocatorFn

Function type that allocates a kinematics solver for a particular group.

Definition at line 56 of file joint_model_group.h.

◆ SolverAllocatorMapFn

Map from group instances to allocator functions & bijections.

Definition at line 59 of file joint_model_group.h.

◆ VariableBoundsMap

using moveit::core::VariableBoundsMap = typedef std::map<std::string, VariableBounds>

Data type for holding mappings from variable names to their bounds.

Definition at line 96 of file joint_model.h.

◆ VariableIndexMap

typedef std::map<std::string, size_t> moveit::core::VariableIndexMap

Data type for holding mappings from variable names to their position in a state vector.

Definition at line 93 of file joint_model.h.

Function Documentation

◆ attachedBodiesToAttachedCollisionObjectMsgs()

void moveit::core::attachedBodiesToAttachedCollisionObjectMsgs ( const std::vector< const AttachedBody * > &  attached_bodies,
std::vector< moveit_msgs::msg::AttachedCollisionObject > &  attached_collision_objs 
)

Convert AttachedBodies to AttachedCollisionObjects.

Parameters
attached_bodiesThe input MoveIt attached body objects
attached_collision_objsThe resultant AttachedCollisionObject messages

Definition at line 444 of file conversions.cpp.

Here is the caller graph for this function:

◆ computeTurnDriveTurnGeometry()

void moveit::core::computeTurnDriveTurnGeometry ( const double *  from,
const double *  to,
const double  min_translational_distance,
double &  dx,
double &  dy,
double &  initial_turn,
double &  drive_angle,
double &  final_turn 
)

Compute the geometry to turn toward the target point, drive straight and then turn to target orientation.

Parameters
[in]fromA vector representing the initial position [x0, y0, theta0]
[in]toA vector representing the target position [x1, y1, theta1]
[in]min_translational_distanceIf the translational distance between from and to is less than this value the motion will be pure rotation (meters)
[out]dxx1 - x0 (meters)
[out]dyy1 - y0 (meters)
[out]initial_turnThe initial turn in radians to face the target
[out]drive_angleThe orientation in radians that the robot will be driving straight at
[out]final_turnThe final turn in radians to the target orientation

Definition at line 166 of file planar_joint_model.cpp.

Here is the caller graph for this function:

◆ errorCodeToString()

std::string moveit::core::errorCodeToString ( const MoveItErrorCode error_code)
inline

Convenience function to translated error message into string.

Parameters
error_codeError code to be translated to a string
Returns
Error code string

Definition at line 82 of file moveit_error_code.h.

Here is the caller graph for this function:

◆ hasJointSpaceJump()

std::optional< int > moveit::core::hasJointSpaceJump ( const std::vector< moveit::core::RobotStatePtr > &  waypoints,
const moveit::core::JointModelGroup group,
const moveit::core::JumpThreshold jump_threshold 
)

Checks if a joint-space path has a jump larger than the given threshold.

This function computes the distance between every pair of adjacent waypoints (for the given group) and checks if that distance is larger than the threshold defined by jump_threshold. If so, it is considered that the path has a jump, and the path index where the jump happens is returned as output. Otherwise the function returns a nullopt.

Definition at line 357 of file cartesian_interpolator.cpp.

Here is the caller graph for this function:

◆ isEmpty() [1/6]

bool moveit::core::isEmpty ( const geometry_msgs::msg::Pose &  msg)

Check if the message contains any non-zero entries.

Definition at line 77 of file message_checks.cpp.

Here is the call graph for this function:

◆ isEmpty() [2/6]

bool moveit::core::isEmpty ( const geometry_msgs::msg::Quaternion &  msg)

Check if the message contains any non-zero entries.

Definition at line 72 of file message_checks.cpp.

◆ isEmpty() [3/6]

bool moveit::core::isEmpty ( const moveit_msgs::msg::Constraints &  msg)

Check if a message specifies constraints.

Definition at line 66 of file message_checks.cpp.

◆ isEmpty() [4/6]

bool moveit::core::isEmpty ( const moveit_msgs::msg::PlanningScene &  msg)

Check if a message includes any information about a planning scene, or whether it is empty.

Definition at line 43 of file message_checks.cpp.

Here is the caller graph for this function:

◆ isEmpty() [5/6]

bool moveit::core::isEmpty ( const moveit_msgs::msg::PlanningSceneWorld &  msg)

Check if a message includes any information about a planning scene world, or whether it is empty.

Definition at line 49 of file message_checks.cpp.

◆ isEmpty() [6/6]

bool moveit::core::isEmpty ( const moveit_msgs::msg::RobotState &  msg)

Check if a message includes any information about a robot state, or whether it is empty.

Definition at line 54 of file message_checks.cpp.

◆ jointStateToRobotState()

bool moveit::core::jointStateToRobotState ( const sensor_msgs::msg::JointState &  joint_state,
RobotState state 
)

Convert a joint state to a MoveIt robot state.

Parameters
joint_stateThe input joint state to be converted
stateThe resultant MoveIt robot state
Returns
True if successful, false if failed for any reason

Definition at line 406 of file conversions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ jointTrajPointToRobotState()

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.

Parameters
joint_trajectoryThe input msg
point_idThe index of the trajectory point in the joint trajectory.
stateThe resultant MoveIt robot state
Returns
True if successful, false if failed for any reason

Definition at line 473 of file conversions.cpp.

Here is the call graph for this function:

◆ loadIKPluginForGroup()

void moveit::core::loadIKPluginForGroup ( const rclcpp::Node::SharedPtr &  node,
JointModelGroup jmg,
const std::string &  base_link,
const std::string &  tip_link,
std::string  plugin = "KDL",
double  timeout = 0.1 
)

Load an IK solver plugin for the given joint model group.

Parameters
[in]jmgjoint model group to load the plugin for
[in]base_linkbase link of chain
[in]tip_linktip link of chain
[in]pluginname of the plugin ("KDL", or full name)
[in]timeoutdefault solver timeout

Definition at line 115 of file robot_model_test_utils.cpp.

Here is the call graph for this function:

◆ loadModelInterface()

urdf::ModelInterfaceSharedPtr moveit::core::loadModelInterface ( const std::string &  robot_name)

Loads a URDF Model Interface from moveit_resources.

Parameters
[in]robot_nameThe name of the robot in moveit_resources to load. This should be the prefix to many of the robot packages. For example, "pr2", "panda", or "fanuc".
Returns
a ModelInterface constructed from robot_name's URDF.

Definition at line 71 of file robot_model_test_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadSRDFModel()

srdf::ModelSharedPtr moveit::core::loadSRDFModel ( const std::string &  robot_name)

Loads an SRDF Model from moveit_resources.

Parameters
[in]robot_nameThe name of the robot in moveit_resources to load. This should be the prefix to many of the robot packages. For example, "pr2", "panda", or "fanuc".
Returns
an SRDF Model constructed from robot_name's URDF and SRDF.

Definition at line 94 of file robot_model_test_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadTestingRobotModel()

moveit::core::RobotModelPtr moveit::core::loadTestingRobotModel ( const std::string &  robot_name)

Loads a robot from moveit_resources.

Parameters
[in]robot_nameThe name of the robot in moveit_resources to load. This should be the prefix to many of the robot packages. For example, "pr2", "panda", or "fanuc".
Returns
a RobotModel constructed from robot_name's URDF and SRDF.

Definition at line 63 of file robot_model_test_utils.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MOVEIT_CLASS_FORWARD() [1/4]

moveit::core::MOVEIT_CLASS_FORWARD ( JointModelGroup  )

◆ MOVEIT_CLASS_FORWARD() [2/4]

moveit::core::MOVEIT_CLASS_FORWARD ( RobotModel  )

◆ MOVEIT_CLASS_FORWARD() [3/4]

moveit::core::MOVEIT_CLASS_FORWARD ( RobotState  )

◆ MOVEIT_CLASS_FORWARD() [4/4]

moveit::core::MOVEIT_CLASS_FORWARD ( Transforms  )

◆ operator<<() [1/2]

std::ostream & moveit::core::operator<< ( std::ostream &  out,
const RobotState s 
)

Operator overload for printing variable bounds to a stream.

Definition at line 2481 of file robot_state.cpp.

Here is the call graph for this function:

◆ operator<<() [2/2]

std::ostream & moveit::core::operator<< ( std::ostream &  out,
const VariableBounds b 
)

Operator overload for printing variable bounds to a stream.

Definition at line 291 of file joint_model.cpp.

◆ robotStateMsgToRobotState() [1/2]

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.

Parameters
robot_stateThe input robot state msg
stateThe resultant MoveIt robot state
copy_attached_bodiesFlag to include attached objects in robot state copy
Returns
True if successful, false if failed for any reason

Definition at line 413 of file conversions.cpp.

Here is the call graph for this function:

◆ robotStateMsgToRobotState() [2/2]

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.

Parameters
tfAn instance of a transforms object
robot_stateThe input robot state msg
stateThe resultant MoveIt robot state
copy_attached_bodiesFlag to include attached objects in robot state copy
Returns
True if successful, false if failed for any reason

Definition at line 421 of file conversions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ robotStateToJointStateMsg()

void moveit::core::robotStateToJointStateMsg ( const RobotState state,
sensor_msgs::msg::JointState &  joint_state 
)

Convert a MoveIt robot state to a joint state message.

Parameters
stateThe input MoveIt robot state object
robot_stateThe resultant JointState message

Definition at line 453 of file conversions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ robotStateToRobotStateMsg()

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.

Parameters
stateThe input MoveIt robot state object
robot_stateThe resultant RobotState *message
copy_attached_bodiesFlag to include attached objects in robot state copy

Definition at line 429 of file conversions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ robotStateToStream() [1/2]

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.

Parameters
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 separator with any symbol, such as a white space

Definition at line 498 of file conversions.cpp.

Here is the call graph for this function:

◆ robotStateToStream() [2/2]

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.

Parameters
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 separator with any symbol, such as a white space

Definition at line 526 of file conversions.cpp.

Here is the call graph for this function:

◆ streamToRobotState()

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.

Parameters
state- the output MoveIt robot state object
line- the input string of joint values
separator- allows to override the comma separator with any symbol, such as a white space
Returns
true on success

Definition at line 563 of file conversions.cpp.

Here is the call graph for this function:

◆ toDouble()

double moveit::core::toDouble ( const std::string &  s)

Converts a std::string to double using the classic C locale.

Exceptions
std::runtime_exceptionif not a valid number

Definition at line 80 of file lexical_casts.cpp.

Here is the caller graph for this function:

◆ toFloat()

float moveit::core::toFloat ( const std::string &  s)

Converts a std::string to float using the classic C locale.

Exceptions
std::runtime_exceptionif not a valid number

Definition at line 85 of file lexical_casts.cpp.

◆ toRealImpl()

template<class OutType >
OutType moveit::core::toRealImpl ( const std::string &  s)

Definition at line 66 of file lexical_casts.cpp.

◆ toString() [1/2]

std::string moveit::core::toString ( double  d)

Convert a double to std::string using the classic C locale.

Definition at line 55 of file lexical_casts.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ toString() [2/2]

std::string moveit::core::toString ( float  f)

Convert a float to std::string using the classic C locale.

Definition at line 60 of file lexical_casts.cpp.

Here is the call graph for this function:

◆ toStringImpl()

template<class InType >
std::string moveit::core::toStringImpl ( InType  t)

Definition at line 46 of file lexical_casts.cpp.

Here is the caller graph for this function: