37 #ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_ 38 #define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_ 40 #include <ompl/base/StateSpace.h> 45 #include "../detail/same_shared_ptr.hpp" 49 typedef boost::function<bool(
const ompl::base::State* from,
const ompl::base::State* to,
const double t,
50 ompl::base::State* state)>
52 typedef boost::function<double(const ompl::base::State* state1, const ompl::base::State* state2)>
DistanceFunction;
57 const robot_model::JointModelGroup* jmg)
66 throw std::runtime_error(
"Group '" + group_name +
"' was not found");
83 GOAL_DISTANCE_KNOWN = 2,
96 flags |= GOAL_DISTANCE_KNOWN;
102 flags |= (VALIDITY_KNOWN | VALIDITY_TRUE);
108 flags |= GOAL_DISTANCE_KNOWN;
114 flags &= ~VALIDITY_TRUE;
115 flags |= VALIDITY_KNOWN;
120 return flags & VALIDITY_KNOWN;
130 return flags & VALIDITY_TRUE;
135 return flags & GOAL_DISTANCE_KNOWN;
140 return flags & IS_START_STATE;
145 return flags & IS_GOAL_STATE;
150 return flags & (IS_START_STATE | IS_GOAL_STATE);
155 flags |= IS_START_STATE;
160 flags |= IS_GOAL_STATE;
174 interpolation_function_ = fun;
179 distance_function_ = fun;
182 virtual ompl::base::State* allocState()
const;
183 virtual void freeState(ompl::base::State* state)
const;
184 virtual unsigned int getDimension()
const;
185 virtual void enforceBounds(ompl::base::State* state)
const;
186 virtual bool satisfiesBounds(
const ompl::base::State* state)
const;
188 virtual void copyState(ompl::base::State* destination,
const ompl::base::State* source)
const;
189 virtual void interpolate(
const ompl::base::State* from,
const ompl::base::State* to,
const double t,
190 ompl::base::State* state)
const;
191 virtual double distance(
const ompl::base::State* state1,
const ompl::base::State* state2)
const;
192 virtual bool equalStates(
const ompl::base::State* state1,
const ompl::base::State* state2)
const;
193 virtual double getMaximumExtent()
const;
194 virtual double getMeasure()
const;
196 virtual unsigned int getSerializationLength()
const;
197 virtual void serialize(
void* serialization,
const ompl::base::State* state)
const;
198 virtual void deserialize(ompl::base::State* state,
const void* serialization)
const;
199 virtual double* getValueAddressAtIndex(ompl::base::State* state,
const unsigned int index)
const;
201 virtual ompl::base::StateSamplerPtr allocDefaultStateSampler()
const;
205 return spec_.robot_model_;
210 return spec_.joint_model_group_;
215 return getJointModelGroup()->getName();
223 virtual void printState(
const ompl::base::State* state, std::ostream& out)
const;
224 virtual void printSettings(std::ostream& out)
const;
227 virtual void setPlanningVolume(
double minX,
double maxX,
double minY,
double maxY,
double minZ,
double maxZ);
231 return spec_.joint_bounds_;
236 virtual void copyToRobotState(robot_state::RobotState& rstate,
const ompl::base::State* state)
const;
240 virtual void copyToOMPLState(ompl::base::State* state,
const robot_state::RobotState& rstate)
const;
252 virtual void copyJointToOMPLState(ompl::base::State* state,
const robot_state::RobotState& robot_state,
255 double getTagSnapToSegment()
const;
256 void setTagSnapToSegment(
double snap);
const ModelBasedStateSpaceSpecification & getSpecification() const
std::vector< const robot_model::JointModel * > joint_model_vector_
const robot_model::JointModelGroup * joint_model_group_
DistanceFunction distance_function_
bool isGoalDistanceKnown() const
std::vector< double > values
void setInterpolationFunction(const InterpolationFunction &fun)
std::vector< robot_model::JointModel::Bounds > joint_bounds_storage_
const robot_model::JointModelGroup * getJointModelGroup() const
ModelBasedStateSpaceSpecification(const robot_model::RobotModelConstPtr &robot_model, const robot_model::JointModelGroup *jmg)
size_t state_values_size_
unsigned int variable_count_
The MoveIt! interface to OMPL.
bool isStartState() const
bool isInputState() const
robot_model::RobotModelConstPtr robot_model_
same_shared_ptr< ModelBasedStateSpace, ompl::base::StateSpacePtr >::type ModelBasedStateSpacePtr
const robot_model::RobotModelConstPtr & getRobotModel() const
const robot_model::JointBoundsVector & getJointsBounds() const
void markInvalid(double d)
void setDistanceFunction(const DistanceFunction &fun)
bool isMarkedValid() const
boost::function< double(const ompl::base::State *state1, const ompl::base::State *state2)> DistanceFunction
ModelBasedStateSpaceSpecification spec_
double tag_snap_to_segment_
robot_model::JointBoundsVector joint_bounds_
ModelBasedStateSpaceSpecification(const robot_model::RobotModelConstPtr &robot_model, const std::string &group_name)
bool isValidityKnown() const
void clearKnownInformation()
double tag_snap_to_segment_complement_
double distance(const urdf::Pose &transform)
InterpolationFunction interpolation_function_
boost::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
const std::string & getJointModelGroupName() const