Core components of MoveIt. More...
| Namespaces | |
| collision_detection | |
| kinematic_constraints | |
| planning_scene | |
| robot_model | |
| robot_state | |
| transforms | |
| Classes | |
| class | AABB | 
| Represents an axis-aligned bounding box.  More... | |
| class | AttachedBody | 
| Object defining bodies that can be attached to robot links.  More... | |
| class | CartesianInterpolator | 
| struct | CartesianPrecision | 
| 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 | 
| struct | JumpThreshold | 
| Struct for containing jump_threshold.  More... | |
| class | LinkModel | 
| A link from the robot. Contains the constant transform applied to the link and its geometry.  More... | |
| struct | MaxEEFStep | 
| Struct for containing max_step for computeCartesianPath.  More... | |
| class | MoveItErrorCode | 
| a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from a function  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 | RobotModelBuilder | 
| Easily build different robot models for testing. Essentially a programmer-friendly light wrapper around URDF and SRDF. Best shown by an example:  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 | 
| 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... | |
| 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)  More... | |
| using | JointBoundsVector = std::vector< const JointModel::Bounds * > | 
| 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 | 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::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 boost::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 | VariableBoundsMap = std::map< std::string, VariableBounds > | 
| Data type for holding mappings from variable names to their bounds.  More... | |
| typedef std::map< std::string, int > | VariableIndexMap | 
| Data type for holding mappings from variable names to their position in a state vector.  More... | |
| Functions | |
| void | attachedBodiesToAttachedCollisionObjectMsgs (const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objs) | 
| Convert AttachedBodies to AttachedCollisionObjects.  More... | |
| static void | checkInterpolationParamBounds (const char LOGNAME[], double t) | 
| 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... | |
| bool | haveSameAttachedObjects (const RobotState &left, const RobotState &right, const std::string &logprefix="") | 
| bool | isArray (const XmlRpc::XmlRpcValue &v, size_t size=0, const std::string &name="", const std::string &description="") | 
| bool | isEmpty (const geometry_msgs::Pose &msg) | 
| Check if the message contains any non-zero entries.  More... | |
| bool | isEmpty (const geometry_msgs::Quaternion &msg) | 
| Check if the message contains any non-zero entries.  More... | |
| bool | isEmpty (const moveit_msgs::Constraints &msg) | 
| Check if a message specifies constraints.  More... | |
| bool | isEmpty (const moveit_msgs::PlanningScene &msg) | 
| Check if a message includes any information about a planning scene, or whether it is empty.  More... | |
| bool | isEmpty (const moveit_msgs::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::RobotState &msg) | 
| Check if a message includes any information about a robot state, or whether it is empty.  More... | |
| bool | isStruct (const XmlRpc::XmlRpcValue &v, const std::vector< std::string > &keys={}, const std::string &name="") | 
| bool | jointStateToRobotState (const sensor_msgs::JointState &joint_state, RobotState &state) | 
| Convert a joint state to a MoveIt robot state.  More... | |
| bool | jointTrajPointToRobotState (const trajectory_msgs::JointTrajectory &trajectory, std::size_t point_id, RobotState &state) | 
| Convert a joint trajectory point to a MoveIt robot state.  More... | |
| void | loadIKPluginForGroup (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... | |
| 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... | |
| moveit::core::RobotModelPtr | loadTestingRobotModel (const std::string &robot_name) | 
| Loads a robot from moveit_resources.  More... | |
| MOVEIT_CLASS_FORWARD (JointModelGroup) | |
| MOVEIT_CLASS_FORWARD (RobotModel) | |
| MOVEIT_CLASS_FORWARD (RobotState) | |
| MOVEIT_CLASS_FORWARD (Transforms) | |
| std::ostream & | operator<< (std::ostream &out, const MoveItErrorCode &e) | 
| std::ostream & | operator<< (std::ostream &out, const RobotState &s) | 
| Operator overload for printing variable bounds to a stream.  More... | |
| std::ostream & | operator<< (std::ostream &out, const VariableBounds &b) | 
| Operator overload for printing variable bounds to a stream.  More... | |
| double | parseDouble (const XmlRpc::XmlRpcValue &v) | 
| parse a double value from a scalar XmlRpc  More... | |
| 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.  More... | |
| 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.  More... | |
| void | robotStateToJointStateMsg (const RobotState &state, sensor_msgs::JointState &joint_state) | 
| Convert a MoveIt robot state to a joint state message.  More... | |
| 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.  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... | |
| 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... | |
| template<class OutType > | |
| OutType | toRealImpl (const std::string &s) | 
| 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... | |
| template<class InType > | |
| std::string | toStringImpl (InType t) | 
| bool | validateAndImproveInterval (const RobotState &start_state, const RobotState &end_state, const Eigen::Isometry3d &start_pose, const Eigen::Isometry3d &end_pose, std::vector< RobotStatePtr > &traj, double &percentage, const double width, const JointModelGroup *group, const LinkModel *link, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback, const kinematics::KinematicsQueryOptions &options, const Eigen::Isometry3d &link_offset) | 
| Variables | |
| const std::string | LOGNAME = "robot_model.jmg" | 
| static const std::size_t | MIN_STEPS_FOR_JUMP_THRESH = 10 | 
| It is recommended that there are at least 10 steps per trajectory for testing jump thresholds with computeCartesianPath. With less than 10 steps it is difficult to choose a jump_threshold parameter that effectively separates valid paths from paths with large joint space jumps.  More... | |
Core components of MoveIt.
| typedef boost::function<void(AttachedBody* body, bool attached)> moveit::core::AttachedBodyCallback | 
Definition at line 115 of file attached_body.h.
| 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 117 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 136 of file robot_state.h.
| using moveit::core::JointBoundsVector = typedef std::vector<const JointModel::Bounds*> | 
Definition at line 132 of file joint_model_group.h.
| using moveit::core::JointModelGroupMap = typedef std::map<std::string, JointModelGroup*> | 
Map of names to instances for JointModelGroup.
Definition at line 127 of file joint_model_group.h.
| using moveit::core::JointModelGroupMapConst = typedef std::map<std::string, const JointModelGroup*> | 
Map of names to const instances for JointModelGroup.
Definition at line 130 of file joint_model_group.h.
| using moveit::core::JointModelMap = typedef std::map<std::string, JointModel*> | 
Map of names to instances for JointModel.
Definition at line 156 of file joint_model.h.
| using moveit::core::JointModelMapConst = typedef std::map<std::string, const JointModel*> | 
Map of names to const instances for JointModel.
Definition at line 159 of file joint_model.h.
| typedef std::map<std::string, LinkModel*> moveit::core::LinkModelMap | 
Map of names to instances for LinkModel.
Definition at line 58 of file link_model.h.
| 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.
| 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 68 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 118 of file joint_model_group.h.
| using moveit::core::SolverAllocatorMapFn = typedef std::map<const JointModelGroup*, SolverAllocatorFn> | 
Map from group instances to allocator functions & bijections.
Definition at line 124 of file joint_model_group.h.
| using moveit::core::VariableBoundsMap = typedef std::map<std::string, VariableBounds> | 
Data type for holding mappings from variable names to their bounds.
Definition at line 153 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 147 of file joint_model.h.
| void moveit::core::attachedBodiesToAttachedCollisionObjectMsgs | ( | const std::vector< const AttachedBody * > & | attached_bodies, | 
| std::vector< moveit_msgs::AttachedCollisionObject > & | attached_collision_objs | ||
| ) | 
Convert AttachedBodies to AttachedCollisionObjects.
| attached_bodies | The input MoveIt attached body objects | 
| attached_collision_objs | The resultant AttachedCollisionObject messages | 
Definition at line 487 of file conversions.cpp.
| 
 | inlinestatic | 
Definition at line 132 of file robot_model.h.
| 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.
| [in] | from | A vector representing the initial position [x0, y0, theta0] | 
| [in] | to | A vector representing the target position [x1, y1, theta1] | 
| [in] | min_translational_distance | If the translational distance between fromandtois less than this value the motion will be pure rotation (meters) | 
| [out] | dx | x1 - x0 (meters) | 
| [out] | dy | y1 - y0 (meters) | 
| [out] | initial_turn | The initial turn in radians to face the target | 
| [out] | drive_angle | The orientation in radians that the robot will be driving straight at | 
| [out] | final_turn | The final turn in radians to the target orientation | 
Definition at line 210 of file planar_joint_model.cpp.
| bool moveit::core::haveSameAttachedObjects | ( | const RobotState & | left, | 
| const RobotState & | right, | ||
| const std::string & | logprefix = "" | ||
| ) | 
Check that both RobotStates have the same set of attached objects
Definition at line 2429 of file robot_state.cpp.
| bool moveit::core::isArray | ( | const XmlRpc::XmlRpcValue & | v, | 
| size_t | size = 0, | ||
| const std::string & | name = "", | ||
| const std::string & | description = "" | ||
| ) | 
check that v is an array of given size
| size | check that array has given size, zero value allows for array size | 
| name | if non-empty, print a warning message "name is not an array[size]" | 
| description | if non-empty, serves as a descriptor for array items | 
Definition at line 119 of file xmlrpc_casts.cpp.
| bool moveit::core::isEmpty | ( | const geometry_msgs::Pose & | msg | ) | 
Check if the message contains any non-zero entries.
Definition at line 141 of file message_checks.cpp.
| bool moveit::core::isEmpty | ( | const geometry_msgs::Quaternion & | msg | ) | 
Check if the message contains any non-zero entries.
Definition at line 136 of file message_checks.cpp.
| bool moveit::core::isEmpty | ( | const moveit_msgs::Constraints & | msg | ) | 
Check if a message specifies constraints.
Definition at line 130 of file message_checks.cpp.
| bool moveit::core::isEmpty | ( | const moveit_msgs::PlanningScene & | msg | ) | 
Check if a message includes any information about a planning scene, or whether it is empty.
Definition at line 107 of file message_checks.cpp.
| bool moveit::core::isEmpty | ( | const moveit_msgs::PlanningSceneWorld & | msg | ) | 
Check if a message includes any information about a planning scene world, or whether it is empty.
Definition at line 113 of file message_checks.cpp.
| bool moveit::core::isEmpty | ( | const moveit_msgs::RobotState & | msg | ) | 
Check if a message includes any information about a robot state, or whether it is empty.
Definition at line 118 of file message_checks.cpp.
| bool moveit::core::isStruct | ( | const XmlRpc::XmlRpcValue & | v, | 
| const std::vector< std::string > & | keys = {}, | ||
| const std::string & | name = "" | ||
| ) | 
check that v is a struct with given keys
| keys | list of required keys | 
| name | if non-empty, print a warning message "name is not a struct with keys ..." | 
Definition at line 131 of file xmlrpc_casts.cpp.
| 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 451 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 516 of file conversions.cpp.
| void moveit::core::loadIKPluginForGroup | ( | 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.
| [in] | jmg | joint model group to load the plugin for | 
| [in] | base_link | base link of chain | 
| [in] | tip_link | tip link of chain | 
| [in] | plugin | name of the plugin ("KDL", or full name) | 
| [in] | timeout | default solver timeout | 
Definition at line 165 of file robot_model_test_utils.cpp.
| urdf::ModelInterfaceSharedPtr moveit::core::loadModelInterface | ( | const std::string & | robot_name | ) | 
Loads a URDF Model Interface from moveit_resources.
| [in] | robot_name | The 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". | 
Definition at line 126 of file robot_model_test_utils.cpp.
| srdf::ModelSharedPtr moveit::core::loadSRDFModel | ( | const std::string & | robot_name | ) | 
Loads an SRDF Model from moveit_resources.
| [in] | robot_name | The 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". | 
Definition at line 147 of file robot_model_test_utils.cpp.
| moveit::core::RobotModelPtr moveit::core::loadTestingRobotModel | ( | const std::string & | robot_name | ) | 
Loads a robot from moveit_resources.
| [in] | robot_name | The 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". | 
Definition at line 117 of file robot_model_test_utils.cpp.
| moveit::core::MOVEIT_CLASS_FORWARD | ( | JointModelGroup | ) | 
| moveit::core::MOVEIT_CLASS_FORWARD | ( | RobotModel | ) | 
| moveit::core::MOVEIT_CLASS_FORWARD | ( | RobotState | ) | 
| moveit::core::MOVEIT_CLASS_FORWARD | ( | Transforms | ) | 
| std::ostream & moveit::core::operator<< | ( | std::ostream & | out, | 
| const MoveItErrorCode & | e | ||
| ) | 
Definition at line 166 of file moveit_error_code.cpp.
| std::ostream & moveit::core::operator<< | ( | std::ostream & | out, | 
| const RobotState & | s | ||
| ) | 
Operator overload for printing variable bounds to a stream.
Definition at line 2423 of file robot_state.cpp.
| std::ostream & moveit::core::operator<< | ( | std::ostream & | out, | 
| const VariableBounds & | b | ||
| ) | 
Operator overload for printing variable bounds to a stream.
Definition at line 309 of file joint_model.cpp.
| double moveit::core::parseDouble | ( | const XmlRpc::XmlRpcValue & | v | ) | 
parse a double value from a scalar XmlRpc
Definition at line 109 of file xmlrpc_casts.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 458 of file conversions.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 465 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 496 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 473 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 541 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 569 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 606 of file conversions.cpp.
| double moveit::core::toDouble | ( | const std::string & | s | ) | 
Converts a std::string to double using the classic C locale.
| std::runtime_exception | if not a valid number | 
Definition at line 145 of file lexical_casts.cpp.
| float moveit::core::toFloat | ( | const std::string & | s | ) | 
Converts a std::string to float using the classic C locale.
| std::runtime_exception | if not a valid number | 
Definition at line 150 of file lexical_casts.cpp.
| OutType moveit::core::toRealImpl | ( | const std::string & | s | ) | 
Definition at line 131 of file lexical_casts.cpp.
| std::string moveit::core::toString | ( | double | d | ) | 
Convert a double to std::string using the classic C locale.
Definition at line 120 of file lexical_casts.cpp.
| std::string moveit::core::toString | ( | float | f | ) | 
Convert a float to std::string using the classic C locale.
Definition at line 125 of file lexical_casts.cpp.
| std::string moveit::core::toStringImpl | ( | InType | t | ) | 
Definition at line 111 of file lexical_casts.cpp.
| bool moveit::core::validateAndImproveInterval | ( | const RobotState & | start_state, | 
| const RobotState & | end_state, | ||
| const Eigen::Isometry3d & | start_pose, | ||
| const Eigen::Isometry3d & | end_pose, | ||
| std::vector< RobotStatePtr > & | traj, | ||
| double & | percentage, | ||
| const double | width, | ||
| const JointModelGroup * | group, | ||
| const LinkModel * | link, | ||
| const CartesianPrecision & | precision, | ||
| const GroupStateValidityCallbackFn & | validCallback, | ||
| const kinematics::KinematicsQueryOptions & | options, | ||
| const Eigen::Isometry3d & | link_offset | ||
| ) | 
Definition at line 123 of file cartesian_interpolator.cpp.
| const std::string moveit::core::LOGNAME = "robot_model.jmg" | 
Definition at line 165 of file joint_model_group.cpp.
| 
 | static | 
It is recommended that there are at least 10 steps per trajectory for testing jump thresholds with computeCartesianPath. With less than 10 steps it is difficult to choose a jump_threshold parameter that effectively separates valid paths from paths with large joint space jumps.
Definition at line 119 of file cartesian_interpolator.cpp.