Public Member Functions | Static Public Attributes | List of all members
ompl_interface::JointModelStateSpace Class Reference

#include <joint_model_state_space.h>

Inheritance diagram for ompl_interface::JointModelStateSpace:
Inheritance graph
[legend]

Public Member Functions

const std::string & getParameterizationType () const override
 
 JointModelStateSpace (const ModelBasedStateSpaceSpecification &spec)
 
- Public Member Functions inherited from ompl_interface::ModelBasedStateSpace
ompl::base::StateSamplerPtr allocDefaultStateSampler () const override
 
ompl::base::State * allocState () const override
 
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...
 
void copyState (ompl::base::State *destination, const ompl::base::State *source) const override
 
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 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...
 
void deserialize (ompl::base::State *state, const void *serialization) const override
 
double distance (const ompl::base::State *state1, const ompl::base::State *state2) const override
 
void enforceBounds (ompl::base::State *state) const override
 
bool equalStates (const ompl::base::State *state1, const ompl::base::State *state2) const override
 
void freeState (ompl::base::State *state) const override
 
unsigned int getDimension () const override
 
const moveit::core::JointModelGroupgetJointModelGroup () const
 
const std::string & getJointModelGroupName () const
 
const moveit::core::JointBoundsVectorgetJointsBounds () const
 
double getMaximumExtent () const override
 
double getMeasure () const override
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
unsigned int getSerializationLength () const override
 
const ModelBasedStateSpaceSpecificationgetSpecification () const
 
double getTagSnapToSegment () const
 
double * getValueAddressAtIndex (ompl::base::State *state, const unsigned int index) const override
 
void interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
 
 ModelBasedStateSpace (ModelBasedStateSpaceSpecification spec)
 
void printSettings (std::ostream &out) const override
 
void printState (const ompl::base::State *state, std::ostream &out) const override
 
bool satisfiesBounds (const ompl::base::State *state) const override
 
void serialize (void *serialization, const ompl::base::State *state) const override
 
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)
 
 ~ModelBasedStateSpace () override
 

Static Public Attributes

static const std::string PARAMETERIZATION_TYPE = "JointModel"
 

Additional Inherited Members

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

Detailed Description

Definition at line 75 of file joint_model_state_space.h.

Constructor & Destructor Documentation

◆ JointModelStateSpace()

ompl_interface::JointModelStateSpace::JointModelStateSpace ( const ModelBasedStateSpaceSpecification spec)

Definition at line 41 of file joint_model_state_space.cpp.

Member Function Documentation

◆ getParameterizationType()

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

Implements ompl_interface::ModelBasedStateSpace.

Definition at line 114 of file joint_model_state_space.h.

Member Data Documentation

◆ PARAMETERIZATION_TYPE

const std::string ompl_interface::JointModelStateSpace::PARAMETERIZATION_TYPE = "JointModel"
static

Definition at line 110 of file joint_model_state_space.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Sat Apr 27 2024 02:26:21