|  | 
|  | JointModelStateSpace (const ModelBasedStateSpaceSpecification &spec) | 
|  | 
| virtual ompl::base::StateSamplerPtr | allocDefaultStateSampler () const | 
|  | 
| virtual ompl::base::State * | allocState () const | 
|  | 
| virtual void | copyJointToOMPLState (ompl::base::State *state, const robot_state::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const | 
|  | Copy a single joint's values (which might have multiple variables) from a MoveIt! robot_state to an OMPL state.  More... 
 | 
|  | 
| virtual void | copyState (ompl::base::State *destination, const ompl::base::State *source) const | 
|  | 
| virtual void | copyToOMPLState (ompl::base::State *state, const robot_state::RobotState &rstate) const | 
|  | Copy the data from a set of joint states to an OMPL state.  More... 
 | 
|  | 
| virtual void | copyToRobotState (robot_state::RobotState &rstate, const ompl::base::State *state) const | 
|  | Copy the data from an OMPL state to a set of joint states.  More... 
 | 
|  | 
| virtual void | deserialize (ompl::base::State *state, const void *serialization) const | 
|  | 
| virtual double | distance (const ompl::base::State *state1, const ompl::base::State *state2) const | 
|  | 
| virtual void | enforceBounds (ompl::base::State *state) const | 
|  | 
| virtual bool | equalStates (const ompl::base::State *state1, const ompl::base::State *state2) const | 
|  | 
| virtual void | freeState (ompl::base::State *state) const | 
|  | 
| virtual unsigned int | getDimension () const | 
|  | 
| const robot_model::JointModelGroup * | getJointModelGroup () const | 
|  | 
| const std::string & | getJointModelGroupName () const | 
|  | 
| const robot_model::JointBoundsVector & | getJointsBounds () const | 
|  | 
| virtual double | getMaximumExtent () const | 
|  | 
| virtual double | getMeasure () const | 
|  | 
| const robot_model::RobotModelConstPtr & | getRobotModel () const | 
|  | 
| virtual unsigned int | getSerializationLength () const | 
|  | 
| const ModelBasedStateSpaceSpecification & | getSpecification () const | 
|  | 
| double | getTagSnapToSegment () const | 
|  | 
| virtual double * | getValueAddressAtIndex (ompl::base::State *state, const unsigned int index) const | 
|  | 
| virtual void | interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const | 
|  | 
|  | ModelBasedStateSpace (const ModelBasedStateSpaceSpecification &spec) | 
|  | 
| virtual void | printSettings (std::ostream &out) const | 
|  | 
| virtual void | printState (const ompl::base::State *state, std::ostream &out) const | 
|  | 
| virtual bool | satisfiesBounds (const ompl::base::State *state) const | 
|  | 
| virtual void | serialize (void *serialization, const ompl::base::State *state) const | 
|  | 
| void | setDistanceFunction (const DistanceFunction &fun) | 
|  | 
| void | setInterpolationFunction (const InterpolationFunction &fun) | 
|  | 
| virtual void | setPlanningVolume (double minX, double maxX, double minY, double maxY, double minZ, double maxZ) | 
|  | Set the planning volume for the possible SE2 and/or SE3 components of the state space.  More... 
 | 
|  | 
| void | setTagSnapToSegment (double snap) | 
|  | 
| virtual | ~ModelBasedStateSpace () | 
|  | 
Definition at line 44 of file joint_model_state_space.h.