Go to the documentation of this file.
39 #include <ompl/base/StateSpace.h>
47 typedef std::function<bool(
const ompl::base::State* from,
const ompl::base::State* to,
const double t,
48 ompl::base::State* state)>
50 typedef std::function<double(
const ompl::base::State* state1,
const ompl::base::State* state2)>
DistanceFunction;
52 struct ModelBasedStateSpaceSpecification
64 throw std::runtime_error(
"Group '" + group_name +
"' was not found");
74 class ModelBasedStateSpace :
public ompl::base::StateSpace
77 class StateType :
public ompl::base::State
182 ompl::base::State*
allocState()
const override;
183 void freeState(ompl::base::State* state)
const override;
188 void copyState(ompl::base::State* destination,
const ompl::base::State* source)
const override;
189 void interpolate(
const ompl::base::State* from,
const ompl::base::State* to,
const double t,
190 ompl::base::State* state)
const override;
191 double distance(
const ompl::base::State* state1,
const ompl::base::State* state2)
const override;
192 bool equalStates(
const ompl::base::State* state1,
const ompl::base::State* state2)
const override;
197 void serialize(
void* serialization,
const ompl::base::State* state)
const override;
198 void deserialize(ompl::base::State* state,
const void* serialization)
const override;
205 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
225 void printState(
const ompl::base::State* state, std::ostream& out)
const override;
229 virtual void setPlanningVolume(
double minX,
double maxX,
double minY,
double maxY,
double minZ,
double maxZ);
void deserialize(ompl::base::State *state, const void *serialization) const override
bool isInputState() const
std::vector< moveit::core::JointModel::Bounds > joint_bounds_storage_
double getTagSnapToSegment() const
void freeState(ompl::base::State *state) const override
OMPL_CLASS_FORWARD(ModelBasedStateSpace)
void setDistanceFunction(const DistanceFunction &fun)
double tag_snap_to_segment_complement_
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
const std::string & getJointModelGroupName() const
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
The MoveIt interface to OMPL.
unsigned int getSerializationLength() const override
ModelBasedStateSpaceSpecification spec_
double * getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const override
std::vector< const JointModel::Bounds * > JointBoundsVector
const ModelBasedStateSpaceSpecification & getSpecification() const
double getMaximumExtent() const override
void clearKnownInformation()
bool isMarkedValid() const
void printState(const ompl::base::State *state, std::ostream &out) const override
DistanceFunction distance_function_
moveit::core::JointBoundsVector joint_bounds_
moveit::core::RobotModelConstPtr robot_model_
const moveit::core::JointBoundsVector & getJointsBounds() const
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.
ModelBasedStateSpaceSpecification(const moveit::core::RobotModelConstPtr &robot_model, const moveit::core::JointModelGroup *jmg)
const moveit::core::JointModelGroup * joint_model_group_
unsigned int getDimension() const override
bool satisfiesBounds(const ompl::base::State *state) const override
const std::string & getName() const
const moveit::core::RobotModelConstPtr & getRobotModel() const
std::function< double(const ompl::base::State *state1, const ompl::base::State *state2)> DistanceFunction
double tag_snap_to_segment_
~ModelBasedStateSpace() override
bool isValidityKnown() const
void serialize(void *serialization, const ompl::base::State *state) const override
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
void setInterpolationFunction(const InterpolationFunction &fun)
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
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.
size_t state_values_size_
double getMeasure() const override
ModelBasedStateSpace(ModelBasedStateSpaceSpecification spec)
virtual const std::string & getParameterizationType() const =0
bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const override
bool isGoalDistanceKnown() const
void enforceBounds(ompl::base::State *state) const override
void setTagSnapToSegment(double snap)
const moveit::core::JointModelGroup * getJointModelGroup() const
void printSettings(std::ostream &out) 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 OM...
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
bool isStartState() const
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.
std::vector< const moveit::core::JointModel * > joint_model_vector_
ompl::base::State * allocState() const override
unsigned int variable_count_
InterpolationFunction interpolation_function_
ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:10