moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Protected Attributes | List of all members
ompl_interface::ModelBasedStateSpace Class Referenceabstract

#include <model_based_state_space.h>

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

Classes

class  StateType
 

Public Member Functions

 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
 
virtual const std::string & getParameterizationType () const =0
 
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
 
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...
 
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 copyToOMPLState (ompl::base::State *state, const moveit::core::RobotState &rstate) const
 Copy the data from a set of joint states to an OMPL state. 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)
 

Protected Attributes

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 74 of file model_based_state_space.h.

Constructor & Destructor Documentation

◆ ModelBasedStateSpace()

ompl_interface::ModelBasedStateSpace::ModelBasedStateSpace ( ModelBasedStateSpaceSpecification  spec)

expose parameters

Definition at line 51 of file model_based_state_space.cpp.

Here is the call graph for this function:

◆ ~ModelBasedStateSpace()

ompl_interface::ModelBasedStateSpace::~ModelBasedStateSpace ( )
overridedefault

Member Function Documentation

◆ allocDefaultStateSampler()

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

Definition at line 269 of file model_based_state_space.cpp.

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

◆ allocState()

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

Definition at line 112 of file model_based_state_space.cpp.

Here is the caller graph for this function:

◆ copyJointToOMPLState()

void ompl_interface::ModelBasedStateSpace::copyJointToOMPLState ( ompl::base::State *  state,
const moveit::core::RobotState robot_state,
const moveit::core::JointModel joint_model,
int  ompl_state_joint_index 
) const
virtual

Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OMPL state.

Parameters
state- output OMPL state with single joint modified
robot_state- input MoveIt state to get the joint value from
joint_model- the joint to copy values of
ompl_state_joint_index- the index of the joint in the ompl state (passed in for efficiency, you should cache this index) e.g. ompl_state_joint_index = joint_model_group_->getVariableGroupIndex("virtual_joint");

Reimplemented in ompl_interface::ConstrainedPlanningStateSpace.

Definition at line 356 of file model_based_state_space.cpp.

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

◆ copyState()

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

Definition at line 125 of file model_based_state_space.cpp.

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

◆ copyToOMPLState()

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

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

Reimplemented in ompl_interface::PoseModelStateSpace, and ompl_interface::ConstrainedPlanningStateSpace.

Definition at line 349 of file model_based_state_space.cpp.

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

◆ copyToRobotState()

void ompl_interface::ModelBasedStateSpace::copyToRobotState ( moveit::core::RobotState rstate,
const ompl::base::State *  state 
) const
virtual

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

Reimplemented in ompl_interface::ConstrainedPlanningStateSpace.

Definition at line 343 of file model_based_state_space.cpp.

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

◆ deserialize()

void ompl_interface::ModelBasedStateSpace::deserialize ( ompl::base::State *  state,
const void *  serialization 
) const
override

Definition at line 144 of file model_based_state_space.cpp.

◆ distance()

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

Definition at line 176 of file model_based_state_space.cpp.

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

◆ enforceBounds()

void ompl_interface::ModelBasedStateSpace::enforceBounds ( ompl::base::State *  state) const
override

Definition at line 199 of file model_based_state_space.cpp.

Here is the call graph for this function:

◆ equalStates()

bool ompl_interface::ModelBasedStateSpace::equalStates ( const ompl::base::State *  state1,
const ompl::base::State *  state2 
) const
override

Definition at line 188 of file model_based_state_space.cpp.

◆ freeState()

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

Definition at line 119 of file model_based_state_space.cpp.

Here is the caller graph for this function:

◆ getDimension()

unsigned int ompl_interface::ModelBasedStateSpace::getDimension ( ) const
override

Definition at line 150 of file model_based_state_space.cpp.

◆ getJointModelGroup()

const moveit::core::JointModelGroup* ompl_interface::ModelBasedStateSpace::getJointModelGroup ( ) const
inline

Definition at line 210 of file model_based_state_space.h.

Here is the caller graph for this function:

◆ getJointModelGroupName()

const std::string& ompl_interface::ModelBasedStateSpace::getJointModelGroupName ( ) const
inline

Definition at line 215 of file model_based_state_space.h.

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

◆ getJointsBounds()

const moveit::core::JointBoundsVector& ompl_interface::ModelBasedStateSpace::getJointsBounds ( ) const
inline

Definition at line 231 of file model_based_state_space.h.

◆ getMaximumExtent()

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

Definition at line 158 of file model_based_state_space.cpp.

Here is the call graph for this function:

◆ getMeasure()

double ompl_interface::ModelBasedStateSpace::getMeasure ( ) const
override

Definition at line 163 of file model_based_state_space.cpp.

◆ getParameterizationType()

virtual const std::string& ompl_interface::ModelBasedStateSpace::getParameterizationType ( ) const
pure virtual

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& ompl_interface::ModelBasedStateSpace::getRobotModel ( ) const
inline

Definition at line 205 of file model_based_state_space.h.

◆ getSerializationLength()

unsigned int ompl_interface::ModelBasedStateSpace::getSerializationLength ( ) const
override

Definition at line 133 of file model_based_state_space.cpp.

◆ getSpecification()

const ModelBasedStateSpaceSpecification& ompl_interface::ModelBasedStateSpace::getSpecification ( ) const
inline

Definition at line 220 of file model_based_state_space.h.

◆ getTagSnapToSegment()

double ompl_interface::ModelBasedStateSpace::getTagSnapToSegment ( ) const

Definition at line 91 of file model_based_state_space.cpp.

Here is the caller graph for this function:

◆ getValueAddressAtIndex()

double * ompl_interface::ModelBasedStateSpace::getValueAddressAtIndex ( ompl::base::State *  state,
const unsigned int  index 
) const
override

Definition at line 238 of file model_based_state_space.cpp.

Here is the caller graph for this function:

◆ interpolate()

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

Definition at line 210 of file model_based_state_space.cpp.

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

◆ printSettings()

void ompl_interface::ModelBasedStateSpace::printSettings ( std::ostream &  out) const
override

Definition at line 308 of file model_based_state_space.cpp.

◆ printState()

void ompl_interface::ModelBasedStateSpace::printState ( const ompl::base::State *  state,
std::ostream &  out 
) const
override

Definition at line 313 of file model_based_state_space.cpp.

Here is the call graph for this function:

◆ satisfiesBounds()

bool ompl_interface::ModelBasedStateSpace::satisfiesBounds ( const ompl::base::State *  state) const
override

Definition at line 204 of file model_based_state_space.cpp.

Here is the call graph for this function:

◆ serialize()

void ompl_interface::ModelBasedStateSpace::serialize ( void *  serialization,
const ompl::base::State *  state 
) const
override

Definition at line 138 of file model_based_state_space.cpp.

◆ setDistanceFunction()

void ompl_interface::ModelBasedStateSpace::setDistanceFunction ( const DistanceFunction fun)
inline

Definition at line 177 of file model_based_state_space.h.

◆ setInterpolationFunction()

void ompl_interface::ModelBasedStateSpace::setInterpolationFunction ( const InterpolationFunction fun)
inline

Definition at line 172 of file model_based_state_space.h.

◆ setPlanningVolume()

void ompl_interface::ModelBasedStateSpace::setPlanningVolume ( double  minX,
double  maxX,
double  minY,
double  maxY,
double  minZ,
double  maxZ 
)
virtual

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 245 of file model_based_state_space.cpp.

Here is the caller graph for this function:

◆ setTagSnapToSegment()

void ompl_interface::ModelBasedStateSpace::setTagSnapToSegment ( double  snap)

Definition at line 96 of file model_based_state_space.cpp.

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

Member Data Documentation

◆ distance_function_

DistanceFunction ompl_interface::ModelBasedStateSpace::distance_function_
protected

Definition at line 268 of file model_based_state_space.h.

◆ interpolation_function_

InterpolationFunction ompl_interface::ModelBasedStateSpace::interpolation_function_
protected

Definition at line 267 of file model_based_state_space.h.

◆ joint_bounds_storage_

std::vector<moveit::core::JointModel::Bounds> ompl_interface::ModelBasedStateSpace::joint_bounds_storage_
protected

Definition at line 262 of file model_based_state_space.h.

◆ joint_model_vector_

std::vector<const moveit::core::JointModel*> ompl_interface::ModelBasedStateSpace::joint_model_vector_
protected

Definition at line 263 of file model_based_state_space.h.

◆ spec_

ModelBasedStateSpaceSpecification ompl_interface::ModelBasedStateSpace::spec_
protected

Definition at line 261 of file model_based_state_space.h.

◆ state_values_size_

size_t ompl_interface::ModelBasedStateSpace::state_values_size_
protected

Definition at line 265 of file model_based_state_space.h.

◆ tag_snap_to_segment_

double ompl_interface::ModelBasedStateSpace::tag_snap_to_segment_
protected

Definition at line 270 of file model_based_state_space.h.

◆ tag_snap_to_segment_complement_

double ompl_interface::ModelBasedStateSpace::tag_snap_to_segment_complement_
protected

Definition at line 271 of file model_based_state_space.h.

◆ variable_count_

unsigned int ompl_interface::ModelBasedStateSpace::variable_count_
protected

Definition at line 264 of file model_based_state_space.h.


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