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

 JointModelStateSpace (const ModelBasedStateSpaceSpecification &spec)
 
- Public Member Functions inherited from ompl_interface::ModelBasedStateSpace
virtual ompl::base::StateSamplerPtr allocDefaultStateSampler () const
 
virtual ompl::base::State * allocState () const
 
virtual void copyJointToOMPLState (ompl::base::State *state, const robot_state::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...
 
virtual void copyState (ompl::base::State *destination, const ompl::base::State *source) const
 
virtual void copyToOMPLState (ompl::base::State *state, const robot_state::RobotState &rstate) const
 Copy the data from a set of joint states to an OMPL state. More...
 
virtual void copyToRobotState (robot_state::RobotState &rstate, const ompl::base::State *state) const
 Copy the data from an OMPL state to a set of joint states. More...
 
virtual void deserialize (ompl::base::State *state, const void *serialization) const
 
virtual double distance (const ompl::base::State *state1, const ompl::base::State *state2) const
 
virtual void enforceBounds (ompl::base::State *state) const
 
virtual bool equalStates (const ompl::base::State *state1, const ompl::base::State *state2) const
 
virtual void freeState (ompl::base::State *state) const
 
virtual unsigned int getDimension () const
 
const robot_model::JointModelGroup * getJointModelGroup () const
 
const std::string & getJointModelGroupName () const
 
const robot_model::JointBoundsVectorgetJointsBounds () const
 
virtual double getMaximumExtent () const
 
virtual double getMeasure () const
 
const robot_model::RobotModelConstPtr & getRobotModel () const
 
virtual unsigned int getSerializationLength () const
 
const ModelBasedStateSpaceSpecificationgetSpecification () const
 
double getTagSnapToSegment () const
 
virtual double * getValueAddressAtIndex (ompl::base::State *state, const unsigned int index) const
 
virtual void interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
 
 ModelBasedStateSpace (const ModelBasedStateSpaceSpecification &spec)
 
virtual void printSettings (std::ostream &out) const
 
virtual void printState (const ompl::base::State *state, std::ostream &out) const
 
virtual bool satisfiesBounds (const ompl::base::State *state) const
 
virtual void serialize (void *serialization, const ompl::base::State *state) const
 
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)
 
virtual ~ModelBasedStateSpace ()
 

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< robot_model::JointModel::Bounds > joint_bounds_storage_
 
std::vector< const robot_model::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 44 of file joint_model_state_space.h.

Constructor & Destructor Documentation

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

Definition at line 41 of file joint_model_state_space.cpp.

Member Data Documentation

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

Definition at line 47 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 Sun Oct 18 2020 13:18:01