38 #include <boost/bind.hpp> 41 : ompl::base::StateSpace(), spec_(spec)
53 "Joint group '%s' has incorrect bounds specified. Using the default bounds instead.",
89 if (snap < 0.0 || snap > 1.0)
91 "Snap to segment for tags is a ratio. It's value must be between 0.0 and 1.0. " 92 "Value remains as previously set (%lf)",
115 const ompl::base::State* source)
const 130 *
reinterpret_cast<int*
>(serialization) = state->as<
StateType>()->
tag;
136 state->as<
StateType>()->tag = *reinterpret_cast<const int*>(serialization);
137 memcpy(state->as<
StateType>()->
values, reinterpret_cast<const char*>(serialization) +
sizeof(
int),
160 for (std::size_t j = 0; j < bounds.size(); ++j)
162 m *= bounds[j].max_position_ - bounds[j].min_position_;
169 const ompl::base::State* state2)
const 178 const ompl::base::State* state2)
const 182 std::numeric_limits<double>::epsilon())
195 std::numeric_limits<double>::epsilon());
199 const double t, ompl::base::State* state)
const 202 state->as<
StateType>()->clearKnownInformation();
221 const unsigned int index)
const 229 double minZ,
double maxZ)
252 class DefaultStateSampler :
public ompl::base::StateSampler
255 DefaultStateSampler(
const ompl::base::StateSpace* space,
const robot_model::JointModelGroup* group,
256 const robot_model::JointBoundsVector* joint_bounds)
257 : ompl::base::StateSampler(space), joint_model_group_(group), joint_bounds_(joint_bounds)
261 virtual void sampleUniform(ompl::base::State* state)
263 joint_model_group_->getVariableRandomPositions(moveit_rng_, state->as<
StateType>()->
values, *joint_bounds_);
264 state->as<
StateType>()->clearKnownInformation();
267 virtual void sampleUniformNear(ompl::base::State* state,
const ompl::base::State* near,
const double distance)
269 joint_model_group_->getVariableRandomPositionsNearBy(moveit_rng_, state->as<
StateType>()->
values, *joint_bounds_,
271 state->as<
StateType>()->clearKnownInformation();
274 virtual void sampleGaussian(ompl::base::State* state,
const ompl::base::State* mean,
const double stdDev)
276 sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
281 const robot_model::JointModelGroup* joint_model_group_;
282 const robot_model::JointBoundsVector* joint_bounds_;
285 return ompl::base::StateSamplerPtr(static_cast<ompl::base::StateSampler*>(
291 out <<
"ModelBasedStateSpace '" <<
getName() <<
"' at " <<
this << std::endl;
301 for (
int i = 0; i < vc; ++i)
307 out <<
"* start state" << std::endl;
309 out <<
"* goal state" << std::endl;
313 out <<
"* valid state" << std::endl;
315 out <<
"* invalid state" << std::endl;
317 out <<
"Tag: " << state->as<
StateType>()->tag << std::endl;
321 const ompl::base::State* state)
const 328 const robot_state::RobotState& rstate)
const 332 state->as<
StateType>()->clearKnownInformation();
336 const robot_state::RobotState& robot_state,
338 int ompl_state_joint_index)
const 346 state->as<
StateType>()->clearKnownInformation();
std::size_t getVariableCount() const
virtual void enforceBounds(ompl::base::State *state) const
std::vector< const robot_model::JointModel * > joint_model_vector_
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.
const robot_model::JointModelGroup * joint_model_group_
virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const
DistanceFunction distance_function_
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 bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) 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.
virtual unsigned int getSerializationLength() const
#define ROS_WARN_NAMED(name,...)
std::vector< double > values
virtual double getMaximumExtent() const
virtual double * getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const
std::vector< robot_model::JointModel::Bounds > joint_bounds_storage_
size_t state_values_size_
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 O...
std::string getName(void *handle)
unsigned int variable_count_
virtual void deserialize(ompl::base::State *state, const void *serialization) const
virtual void serialize(void *serialization, const ompl::base::State *state) const
virtual ompl::base::State * allocState() const
bool isStartState() const
void setTagSnapToSegment(double snap)
virtual ~ModelBasedStateSpace()
virtual void printState(const ompl::base::State *state, std::ostream &out) const
virtual void printSettings(std::ostream &out) const
bool isMarkedValid() const
virtual void freeState(ompl::base::State *state) const
virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
ModelBasedStateSpaceSpecification spec_
double tag_snap_to_segment_
virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const
robot_model::JointBoundsVector joint_bounds_
ModelBasedStateSpace(const ModelBasedStateSpaceSpecification &spec)
virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const
int getFirstVariableIndex() const
bool isValidityKnown() const
virtual unsigned int getDimension() const
double getTagSnapToSegment() const
#define ROS_ERROR_NAMED(name,...)
virtual bool satisfiesBounds(const ompl::base::State *state) const
virtual double getMeasure() const
double tag_snap_to_segment_complement_
InterpolationFunction interpolation_function_