moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Static Public Attributes | List of all members
ompl_interface::PoseModelStateSpace Class Reference

#include <pose_model_state_space.h>

Inheritance diagram for ompl_interface::PoseModelStateSpace:
Inheritance graph
[legend]
Collaboration diagram for ompl_interface::PoseModelStateSpace:
Collaboration graph
[legend]

Classes

class  StateType
 

Public Member Functions

 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. More...
 
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. More...
 
void sanityChecks () const override
 
const std::string & getParameterizationType () const override
 
- Public Member Functions inherited from ompl_interface::ModelBasedStateSpace
 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::JointModelGroupgetJointModelGroup () const
 
const std::string & getJointModelGroupName () const
 
const ModelBasedStateSpaceSpecificationgetSpecification () const
 
void printState (const ompl::base::State *state, std::ostream &out) const override
 
void printSettings (std::ostream &out) const override
 
const moveit::core::JointBoundsVectorgetJointsBounds () 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. More...
 
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. More...
 
double getTagSnapToSegment () const
 
void setTagSnapToSegment (double snap)
 

Static Public Attributes

static const std::string PARAMETERIZATION_TYPE = "PoseModel"
 

Additional Inherited Members

- Protected Attributes inherited from ompl_interface::ModelBasedStateSpace
ModelBasedStateSpaceSpecification spec_
 
std::vector< moveit::core::JointModel::Boundsjoint_bounds_storage_
 
std::vector< const moveit::core::JointModel * > joint_model_vector_
 
unsigned int variable_count_
 
size_t state_values_size_
 
InterpolationFunction interpolation_function_
 
DistanceFunction distance_function_
 
double tag_snap_to_segment_
 
double tag_snap_to_segment_complement_
 

Detailed Description

Definition at line 44 of file pose_model_state_space.h.

Constructor & Destructor Documentation

◆ PoseModelStateSpace()

ompl_interface::PoseModelStateSpace::PoseModelStateSpace ( const ModelBasedStateSpaceSpecification spec)

Definition at line 49 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ ~PoseModelStateSpace()

ompl_interface::PoseModelStateSpace::~PoseModelStateSpace ( )
overridedefault

Member Function Documentation

◆ allocDefaultStateSampler()

ompl::base::StateSamplerPtr ompl_interface::PoseModelStateSpace::allocDefaultStateSampler ( ) const
override

Definition at line 299 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ allocState()

ompl::base::State * ompl_interface::PoseModelStateSpace::allocState ( ) const
override

Definition at line 89 of file pose_model_state_space.cpp.

◆ computeStateFK()

bool ompl_interface::PoseModelStateSpace::computeStateFK ( ompl::base::State *  state) const

Definition at line 259 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ computeStateIK()

bool ompl_interface::PoseModelStateSpace::computeStateIK ( ompl::base::State *  state) const

Definition at line 273 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ computeStateK()

bool ompl_interface::PoseModelStateSpace::computeStateK ( ompl::base::State *  state) const

Definition at line 287 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ copyState()

void ompl_interface::PoseModelStateSpace::copyState ( ompl::base::State *  destination,
const ompl::base::State *  source 
) const
override

Definition at line 108 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ copyToOMPLState()

void ompl_interface::PoseModelStateSpace::copyToOMPLState ( ompl::base::State *  state,
const moveit::core::RobotState rstate 
) const
overridevirtual

Copy the data from a set of joint states to an OMPL state.

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 342 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ distance()

double ompl_interface::PoseModelStateSpace::distance ( const ompl::base::State *  state1,
const ompl::base::State *  state2 
) const
override

Definition at line 72 of file pose_model_state_space.cpp.

◆ freeState()

void ompl_interface::PoseModelStateSpace::freeState ( ompl::base::State *  state) const
override

Definition at line 100 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ getMaximumExtent()

double ompl_interface::PoseModelStateSpace::getMaximumExtent ( ) const
override

Definition at line 81 of file pose_model_state_space.cpp.

◆ getParameterizationType()

const std::string& ompl_interface::PoseModelStateSpace::getParameterizationType ( ) const
inlineoverridevirtual

Implements ompl_interface::ModelBasedStateSpace.

Definition at line 113 of file pose_model_state_space.h.

◆ interpolate()

void ompl_interface::PoseModelStateSpace::interpolate ( const ompl::base::State *  from,
const ompl::base::State *  to,
const double  t,
ompl::base::State *  state 
) const
override

Definition at line 127 of file pose_model_state_space.cpp.

Here is the call graph for this function:

◆ sanityChecks()

void ompl_interface::PoseModelStateSpace::sanityChecks ( ) const
override

Definition at line 121 of file pose_model_state_space.cpp.

◆ setPlanningVolume()

void ompl_interface::PoseModelStateSpace::setPlanningVolume ( double  minX,
double  maxX,
double  minY,
double  maxY,
double  minZ,
double  maxZ 
)
overridevirtual

Set the planning volume for the possible SE2 and/or SE3 components of the state space.

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 166 of file pose_model_state_space.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ PARAMETERIZATION_TYPE

const std::string ompl_interface::PoseModelStateSpace::PARAMETERIZATION_TYPE = "PoseModel"
static

Definition at line 47 of file pose_model_state_space.h.


The documentation for this class was generated from the following files: