Classes | Public Member Functions | Protected Attributes
ompl_interface::ModelBasedStateSpace Class Reference

#include <model_based_state_space.h>

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

List of all members.

Classes

class  StateType

Public Member Functions

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.
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.
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.
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::JointBoundsVector
getJointsBounds () const
virtual double getMaximumExtent () const
virtual double getMeasure () const
const
robot_model::RobotModelConstPtr & 
getRobotModel () const
virtual unsigned int getSerializationLength () const
const
ModelBasedStateSpaceSpecification
getSpecification () 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.
void setTagSnapToSegment (double snap)
virtual ~ModelBasedStateSpace ()

Protected Attributes

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


Constructor & Destructor Documentation

expose parameters

Definition at line 40 of file model_based_state_space.cpp.

Definition at line 77 of file model_based_state_space.cpp.


Member Function Documentation

ompl::base::StateSamplerPtr ompl_interface::ModelBasedStateSpace::allocDefaultStateSampler ( ) const [virtual]

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 248 of file model_based_state_space.cpp.

ompl::base::State * ompl_interface::ModelBasedStateSpace::allocState ( ) const [virtual]

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 99 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::copyJointToOMPLState ( ompl::base::State *  state,
const robot_state::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");

Definition at line 333 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::copyState ( ompl::base::State *  destination,
const ompl::base::State *  source 
) const [virtual]

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 112 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::copyToOMPLState ( ompl::base::State *  state,
const robot_state::RobotState &  rstate 
) const [virtual]

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 325 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::copyToRobotState ( robot_state::RobotState &  rstate,
const ompl::base::State *  state 
) const [virtual]

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

Definition at line 318 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::deserialize ( ompl::base::State *  state,
const void *  serialization 
) const [virtual]

Definition at line 132 of file model_based_state_space.cpp.

double ompl_interface::ModelBasedStateSpace::distance ( const ompl::base::State *  state1,
const ompl::base::State *  state2 
) const [virtual]

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 166 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::enforceBounds ( ompl::base::State *  state) const [virtual]

Definition at line 185 of file model_based_state_space.cpp.

bool ompl_interface::ModelBasedStateSpace::equalStates ( const ompl::base::State *  state1,
const ompl::base::State *  state2 
) const [virtual]

Definition at line 175 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::freeState ( ompl::base::State *  state) const [virtual]

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 106 of file model_based_state_space.cpp.

unsigned int ompl_interface::ModelBasedStateSpace::getDimension ( ) const [virtual]

Definition at line 139 of file model_based_state_space.cpp.

const robot_model::JointModelGroup* ompl_interface::ModelBasedStateSpace::getJointModelGroup ( ) const [inline]

Definition at line 207 of file model_based_state_space.h.

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

Definition at line 212 of file model_based_state_space.h.

Definition at line 228 of file model_based_state_space.h.

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 147 of file model_based_state_space.cpp.

Definition at line 152 of file model_based_state_space.cpp.

const robot_model::RobotModelConstPtr& ompl_interface::ModelBasedStateSpace::getRobotModel ( ) const [inline]

Definition at line 202 of file model_based_state_space.h.

Definition at line 121 of file model_based_state_space.cpp.

Definition at line 217 of file model_based_state_space.h.

Definition at line 81 of file model_based_state_space.cpp.

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

Definition at line 218 of file model_based_state_space.cpp.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 196 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::printSettings ( std::ostream &  out) const [virtual]

Definition at line 287 of file model_based_state_space.cpp.

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

Definition at line 292 of file model_based_state_space.cpp.

bool ompl_interface::ModelBasedStateSpace::satisfiesBounds ( const ompl::base::State *  state) const [virtual]

Definition at line 190 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::serialize ( void *  serialization,
const ompl::base::State *  state 
) const [virtual]

Definition at line 126 of file model_based_state_space.cpp.

Definition at line 176 of file model_based_state_space.h.

Definition at line 171 of file model_based_state_space.h.

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 226 of file model_based_state_space.cpp.

Definition at line 86 of file model_based_state_space.cpp.


Member Data Documentation

Definition at line 265 of file model_based_state_space.h.

Definition at line 264 of file model_based_state_space.h.

std::vector<robot_model::JointModel::Bounds> ompl_interface::ModelBasedStateSpace::joint_bounds_storage_ [protected]

Definition at line 259 of file model_based_state_space.h.

std::vector<const robot_model::JointModel*> ompl_interface::ModelBasedStateSpace::joint_model_vector_ [protected]

Definition at line 260 of file model_based_state_space.h.

Definition at line 258 of file model_based_state_space.h.

Definition at line 262 of file model_based_state_space.h.

Definition at line 267 of file model_based_state_space.h.

Definition at line 268 of file model_based_state_space.h.

Definition at line 261 of file model_based_state_space.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:27