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

State space to be used in combination with OMPL's constrained planning functionality. More...

#include <constrained_planning_state_space.h>

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

Public Member Functions

 ConstrainedPlanningStateSpace (const ModelBasedStateSpaceSpecification &spec)
 
const std::string & getParameterizationType () const override
 
double * getValueAddressAtIndex (ompl::base::State *ompl_state, const unsigned int index) const override
 
void copyToRobotState (moveit::core::RobotState &robot_state, const ompl::base::State *ompl_state) const override
 Copy the data from an OMPL state to a set of joint states. More...
 
void copyToOMPLState (ompl::base::State *ompl_state, const moveit::core::RobotState &robot_state) const override
 Copy the data from a set of joint states to an OMPL state. More...
 
void copyJointToOMPLState (ompl::base::State *ompl_state, const moveit::core::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const override
 Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OMPL state. More...
 
- 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
 
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
 
double getTagSnapToSegment () const
 
void setTagSnapToSegment (double snap)
 

Static Public Attributes

static const std::string PARAMETERIZATION_TYPE = "ConstrainedPlanningJointModel"
 

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

State space to be used in combination with OMPL's constrained planning functionality.

The state space is called ConstrainedPlanningStateSpace, as in "use this state space for constrained planning". Not to be confused with the ompl::base::ConstrainedStateSpace, which is constrained in the sense that it generates states that satisfy the constraints. This state space does not! OMPL's ompl::base::ConstrainedStateSpace will wrap around ConstrainedPlanningStateSpace.

This class overrides the virtual methods to copy states from OMPL to MoveIt and vice-versa. It is used as state space in the ModelBasedPlanningContextSpecification and can handle general ompl::base::State* pointers that need to be casted to a ompl::Base::ConstrainedStateSpace::StateType, instead of the 'normal' ompl_interface::ModelBasedStateSpace::StateType. This casting looks like this:

ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<StateType>()

where getState() is used to access the underlying state space, which should be an instance of this class.

Definition at line 62 of file constrained_planning_state_space.h.

Constructor & Destructor Documentation

◆ ConstrainedPlanningStateSpace()

ompl_interface::ConstrainedPlanningStateSpace::ConstrainedPlanningStateSpace ( const ModelBasedStateSpaceSpecification spec)

Definition at line 45 of file constrained_planning_state_space.cpp.

Member Function Documentation

◆ copyJointToOMPLState()

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

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 from ompl_interface::ModelBasedStateSpace.

Definition at line 86 of file constrained_planning_state_space.cpp.

Here is the call graph for this function:

◆ copyToOMPLState()

void ompl_interface::ConstrainedPlanningStateSpace::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 74 of file constrained_planning_state_space.cpp.

Here is the call graph for this function:

◆ copyToRobotState()

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

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

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 64 of file constrained_planning_state_space.cpp.

Here is the call graph for this function:

◆ getParameterizationType()

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

◆ getValueAddressAtIndex()

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

Definition at line 51 of file constrained_planning_state_space.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ PARAMETERIZATION_TYPE

const std::string ompl_interface::ConstrainedPlanningStateSpace::PARAMETERIZATION_TYPE = "ConstrainedPlanningJointModel"
static

Definition at line 65 of file constrained_planning_state_space.h.


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