| 
|   | PoseModelStateSpace (const ModelBasedStateSpaceSpecification &spec) | 
|   | 
|   | ~PoseModelStateSpace () override | 
|   | 
| ompl::base::State *  | allocState () const override | 
|   | 
| void  | freeState (ompl::base::State *state) const override | 
|   | 
| void  | copyState (ompl::base::State *destination, const ompl::base::State *source) const override | 
|   | 
| void  | interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override | 
|   | 
| double  | distance (const ompl::base::State *state1, const ompl::base::State *state2) const override | 
|   | 
| double  | getMaximumExtent () const override | 
|   | 
| ompl::base::StateSamplerPtr  | allocDefaultStateSampler () const override | 
|   | 
| bool  | computeStateFK (ompl::base::State *state) const | 
|   | 
| bool  | computeStateIK (ompl::base::State *state) const | 
|   | 
| bool  | computeStateK (ompl::base::State *state) const | 
|   | 
| void  | setPlanningVolume (double minX, double maxX, double minY, double maxY, double minZ, double maxZ) override | 
|   | Set the planning volume for the possible SE2 and/or SE3 components of the state space.  
  | 
|   | 
| void  | copyToOMPLState (ompl::base::State *state, const moveit::core::RobotState &rstate) const override | 
|   | Copy the data from a set of joint states to an OMPL state.  
  | 
|   | 
| void  | sanityChecks () const override | 
|   | 
| const std::string &  | getParameterizationType () const override | 
|   | 
|   | ModelBasedStateSpace (ModelBasedStateSpaceSpecification spec) | 
|   | 
|   | ~ModelBasedStateSpace () override | 
|   | 
| void  | setInterpolationFunction (const InterpolationFunction &fun) | 
|   | 
| void  | setDistanceFunction (const DistanceFunction &fun) | 
|   | 
| ompl::base::State *  | allocState () const override | 
|   | 
| void  | freeState (ompl::base::State *state) const override | 
|   | 
| unsigned int  | getDimension () const override | 
|   | 
| void  | enforceBounds (ompl::base::State *state) const override | 
|   | 
| bool  | satisfiesBounds (const ompl::base::State *state) const override | 
|   | 
| void  | copyState (ompl::base::State *destination, const ompl::base::State *source) const override | 
|   | 
| void  | interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override | 
|   | 
| double  | distance (const ompl::base::State *state1, const ompl::base::State *state2) const override | 
|   | 
| bool  | equalStates (const ompl::base::State *state1, const ompl::base::State *state2) const override | 
|   | 
| double  | getMaximumExtent () const override | 
|   | 
| double  | getMeasure () const override | 
|   | 
| unsigned int  | getSerializationLength () const override | 
|   | 
| void  | serialize (void *serialization, const ompl::base::State *state) const override | 
|   | 
| void  | deserialize (ompl::base::State *state, const void *serialization) const override | 
|   | 
| double *  | getValueAddressAtIndex (ompl::base::State *state, const unsigned int index) const override | 
|   | 
| ompl::base::StateSamplerPtr  | allocDefaultStateSampler () const override | 
|   | 
| const moveit::core::RobotModelConstPtr &  | getRobotModel () const | 
|   | 
| const moveit::core::JointModelGroup *  | getJointModelGroup () const | 
|   | 
| const std::string &  | getJointModelGroupName () const | 
|   | 
| const ModelBasedStateSpaceSpecification &  | getSpecification () const | 
|   | 
| void  | printState (const ompl::base::State *state, std::ostream &out) const override | 
|   | 
| void  | printSettings (std::ostream &out) const override | 
|   | 
| const moveit::core::JointBoundsVector &  | getJointsBounds () const | 
|   | 
| virtual void  | copyToRobotState (moveit::core::RobotState &rstate, const ompl::base::State *state) const | 
|   | Copy the data from an OMPL state to a set of joint states.  
  | 
|   | 
| virtual void  | copyJointToOMPLState (ompl::base::State *state, const moveit::core::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.  
  | 
|   | 
| double  | getTagSnapToSegment () const | 
|   | 
| void  | setTagSnapToSegment (double snap) | 
|   | 
Definition at line 44 of file pose_model_state_space.hpp.