#include <model_based_state_space.h>

Classes | |
| class | StateType |
Public Member Functions | |
| 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::JointModelGroup * | getJointModelGroup () const |
| const std::string & | getJointModelGroupName () const |
| const moveit::core::JointBoundsVector & | getJointsBounds () const |
| double | getMaximumExtent () const override |
| double | getMeasure () const override |
| virtual const std::string & | getParameterizationType () const =0 |
| const moveit::core::RobotModelConstPtr & | getRobotModel () const |
| unsigned int | getSerializationLength () const override |
| const ModelBasedStateSpaceSpecification & | getSpecification () 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 | |
Protected Attributes | |
| DistanceFunction | distance_function_ |
| InterpolationFunction | interpolation_function_ |
| std::vector< moveit::core::JointModel::Bounds > | joint_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_ |
Definition at line 106 of file model_based_state_space.h.
| ompl_interface::ModelBasedStateSpace::ModelBasedStateSpace | ( | ModelBasedStateSpaceSpecification | spec | ) |
expose parameters
Definition at line 45 of file model_based_state_space.cpp.
|
overridedefault |
|
override |
Definition at line 251 of file model_based_state_space.cpp.
|
override |
Definition at line 104 of file model_based_state_space.cpp.
|
virtual |
Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OMPL state.
| 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 336 of file model_based_state_space.cpp.
|
override |
Definition at line 117 of file model_based_state_space.cpp.
|
virtual |
Copy the data from a set of joint states to an OMPL state.
Reimplemented in ompl_interface::PoseModelStateSpace.
Definition at line 328 of file model_based_state_space.cpp.
|
virtual |
Copy the data from an OMPL state to a set of joint states.
Definition at line 321 of file model_based_state_space.cpp.
|
override |
Definition at line 137 of file model_based_state_space.cpp.
|
override |
Definition at line 169 of file model_based_state_space.cpp.
|
override |
Definition at line 188 of file model_based_state_space.cpp.
|
override |
Definition at line 178 of file model_based_state_space.cpp.
|
override |
Definition at line 111 of file model_based_state_space.cpp.
|
override |
Definition at line 143 of file model_based_state_space.cpp.
|
inline |
Definition at line 242 of file model_based_state_space.h.
|
inline |
Definition at line 247 of file model_based_state_space.h.
|
inline |
Definition at line 263 of file model_based_state_space.h.
|
override |
Definition at line 151 of file model_based_state_space.cpp.
|
override |
Definition at line 156 of file model_based_state_space.cpp.
|
pure virtual |
Implemented in ompl_interface::PoseModelStateSpace, and ompl_interface::JointModelStateSpace.
|
inline |
Definition at line 237 of file model_based_state_space.h.
|
override |
Definition at line 126 of file model_based_state_space.cpp.
|
inline |
Definition at line 252 of file model_based_state_space.h.
| double ompl_interface::ModelBasedStateSpace::getTagSnapToSegment | ( | ) | const |
Definition at line 85 of file model_based_state_space.cpp.
|
override |
Definition at line 221 of file model_based_state_space.cpp.
|
override |
Definition at line 199 of file model_based_state_space.cpp.
|
override |
Definition at line 290 of file model_based_state_space.cpp.
|
override |
Definition at line 295 of file model_based_state_space.cpp.
|
override |
Definition at line 193 of file model_based_state_space.cpp.
|
override |
Definition at line 131 of file model_based_state_space.cpp.
|
inline |
Definition at line 209 of file model_based_state_space.h.
|
inline |
Definition at line 204 of file model_based_state_space.h.
|
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 229 of file model_based_state_space.cpp.
| void ompl_interface::ModelBasedStateSpace::setTagSnapToSegment | ( | double | snap | ) |
Definition at line 90 of file model_based_state_space.cpp.
|
protected |
Definition at line 300 of file model_based_state_space.h.
|
protected |
Definition at line 299 of file model_based_state_space.h.
|
protected |
Definition at line 294 of file model_based_state_space.h.
|
protected |
Definition at line 295 of file model_based_state_space.h.
|
protected |
Definition at line 293 of file model_based_state_space.h.
|
protected |
Definition at line 297 of file model_based_state_space.h.
|
protected |
Definition at line 302 of file model_based_state_space.h.
|
protected |
Definition at line 303 of file model_based_state_space.h.
|
protected |
Definition at line 296 of file model_based_state_space.h.