moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <model_based_state_space.h>
Classes | |
class | StateType |
Public Member Functions | |
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 |
virtual const std::string & | getParameterizationType () const =0 |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
const moveit::core::JointModelGroup * | getJointModelGroup () const |
const std::string & | getJointModelGroupName () const |
const ModelBasedStateSpaceSpecification & | getSpecification () 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. | |
const moveit::core::JointBoundsVector & | getJointsBounds () const |
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. | |
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. | |
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. | |
double | getTagSnapToSegment () const |
void | setTagSnapToSegment (double snap) |
Protected Attributes | |
ModelBasedStateSpaceSpecification | spec_ |
std::vector< moveit::core::JointModel::Bounds > | joint_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_ |
Definition at line 74 of file model_based_state_space.h.
ompl_interface::ModelBasedStateSpace::ModelBasedStateSpace | ( | ModelBasedStateSpaceSpecification | spec | ) |
expose parameters
Definition at line 51 of file model_based_state_space.cpp.
|
overridedefault |
|
override |
Definition at line 269 of file model_based_state_space.cpp.
|
override |
Definition at line 112 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"); |
Reimplemented in ompl_interface::ConstrainedPlanningStateSpace.
Definition at line 356 of file model_based_state_space.cpp.
|
override |
Definition at line 125 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::ConstrainedPlanningStateSpace, and ompl_interface::PoseModelStateSpace.
Definition at line 349 of file model_based_state_space.cpp.
|
virtual |
Copy the data from an OMPL state to a set of joint states.
Reimplemented in ompl_interface::ConstrainedPlanningStateSpace.
Definition at line 343 of file model_based_state_space.cpp.
|
override |
Definition at line 144 of file model_based_state_space.cpp.
|
override |
Definition at line 176 of file model_based_state_space.cpp.
|
override |
Definition at line 199 of file model_based_state_space.cpp.
|
override |
Definition at line 188 of file model_based_state_space.cpp.
|
override |
Definition at line 119 of file model_based_state_space.cpp.
|
override |
Definition at line 150 of file model_based_state_space.cpp.
|
inline |
Definition at line 210 of file model_based_state_space.h.
|
inline |
Definition at line 215 of file model_based_state_space.h.
|
inline |
Definition at line 231 of file model_based_state_space.h.
|
override |
Definition at line 158 of file model_based_state_space.cpp.
|
override |
Definition at line 163 of file model_based_state_space.cpp.
|
pure virtual |
|
inline |
Definition at line 205 of file model_based_state_space.h.
|
override |
Definition at line 133 of file model_based_state_space.cpp.
|
inline |
Definition at line 220 of file model_based_state_space.h.
double ompl_interface::ModelBasedStateSpace::getTagSnapToSegment | ( | ) | const |
Definition at line 91 of file model_based_state_space.cpp.
|
override |
Definition at line 238 of file model_based_state_space.cpp.
|
override |
Definition at line 210 of file model_based_state_space.cpp.
|
override |
Definition at line 308 of file model_based_state_space.cpp.
|
override |
Definition at line 313 of file model_based_state_space.cpp.
|
override |
Definition at line 204 of file model_based_state_space.cpp.
|
override |
Definition at line 138 of file model_based_state_space.cpp.
|
inline |
Definition at line 177 of file model_based_state_space.h.
|
inline |
Definition at line 172 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 245 of file model_based_state_space.cpp.
void ompl_interface::ModelBasedStateSpace::setTagSnapToSegment | ( | double | snap | ) |
Definition at line 96 of file model_based_state_space.cpp.
|
protected |
Definition at line 268 of file model_based_state_space.h.
|
protected |
Definition at line 267 of file model_based_state_space.h.
|
protected |
Definition at line 262 of file model_based_state_space.h.
|
protected |
Definition at line 263 of file model_based_state_space.h.
|
protected |
Definition at line 261 of file model_based_state_space.h.
|
protected |
Definition at line 265 of file model_based_state_space.h.
|
protected |
Definition at line 270 of file model_based_state_space.h.
|
protected |
Definition at line 271 of file model_based_state_space.h.
|
protected |
Definition at line 264 of file model_based_state_space.h.