42 constexpr
char LOGNAME[] =
"model_based_state_space";
46 : ompl::base::StateSpace(), spec_(
std::move(spec))
57 ROS_ERROR_NAMED(
LOGNAME,
"Joint group '%s' has incorrect bounds specified. Using the default bounds instead.",
78 params_.declareParam<
double>(
79 "tag_snap_to_segment", [
this](
double tag_snap_to_segment) {
setTagSnapToSegment(tag_snap_to_segment); },
87 return tag_snap_to_segment_;
92 if (snap < 0.0 || snap > 1.0)
94 "Snap to segment for tags is a ratio. It's value must be between 0.0 and 1.0. "
95 "Value remains as previously set (%lf)",
96 tag_snap_to_segment_);
99 tag_snap_to_segment_ = snap;
100 tag_snap_to_segment_complement_ = 1.0 - tag_snap_to_segment_;
107 state->values =
new double[variable_count_];
118 const ompl::base::State* source)
const
128 return state_values_size_ +
sizeof(int);
133 *
reinterpret_cast<int*
>(serialization) = state->as<
StateType>()->
tag;
134 memcpy(
reinterpret_cast<char*
>(serialization) +
sizeof(
int), state->as<
StateType>()->
values, state_values_size_);
139 state->as<
StateType>()->tag = *
reinterpret_cast<const int*
>(serialization);
140 memcpy(state->as<
StateType>()->
values,
reinterpret_cast<const char*
>(serialization) +
sizeof(
int), state_values_size_);
147 d += i->getStateSpaceDimension();
153 return spec_.joint_model_group_->getMaximumExtent(spec_.joint_bounds_);
163 m *=
bound.max_position_ -
bound.min_position_;
170 const ompl::base::State* state2)
const
172 if (distance_function_)
173 return distance_function_(state1, state2);
179 const ompl::base::State* state2)
const
181 for (
unsigned int i = 0; i < variable_count_; ++i)
183 std::numeric_limits<double>::epsilon())
190 spec_.joint_model_group_->enforcePositionBounds(state->as<
StateType>()->
values, spec_.joint_bounds_);
195 return spec_.joint_model_group_->satisfiesPositionBounds(state->as<
StateType>()->
values, spec_.joint_bounds_,
196 std::numeric_limits<double>::epsilon());
200 const double t, ompl::base::State* state)
const
203 state->as<
StateType>()->clearKnownInformation();
205 if (!interpolation_function_ || !interpolation_function_(from, to,
t, state))
212 if (from->as<
StateType>()->
tag >= 0 &&
t < 1.0 - tag_snap_to_segment_)
214 else if (to->as<
StateType>()->
tag >= 0 &&
t > tag_snap_to_segment_)
222 const unsigned int index)
const
224 if (
index >= variable_count_)
230 double minZ,
double maxZ)
232 for (std::size_t i = 0; i < joint_model_vector_.size(); ++i)
235 joint_bounds_storage_[i][0].min_position_ = minX;
236 joint_bounds_storage_[i][0].max_position_ = maxX;
237 joint_bounds_storage_[i][1].min_position_ = minY;
238 joint_bounds_storage_[i][1].max_position_ = maxY;
242 joint_bounds_storage_[i][0].min_position_ = minX;
243 joint_bounds_storage_[i][0].max_position_ = maxX;
244 joint_bounds_storage_[i][1].min_position_ = minY;
245 joint_bounds_storage_[i][1].max_position_ = maxY;
246 joint_bounds_storage_[i][2].min_position_ = minZ;
247 joint_bounds_storage_[i][2].max_position_ = maxZ;
253 class DefaultStateSampler :
public ompl::base::StateSampler
258 : ompl::base::StateSampler(space), joint_model_group_(group), joint_bounds_(joint_bounds)
262 void sampleUniform(ompl::base::State* state)
override
264 joint_model_group_->getVariableRandomPositions(moveit_rng_, state->as<
StateType>()->
values, *joint_bounds_);
265 state->as<
StateType>()->clearKnownInformation();
268 void sampleUniformNear(ompl::base::State* state,
const ompl::base::State* near,
const double distance)
override
270 joint_model_group_->getVariableRandomPositionsNearBy(moveit_rng_, state->as<
StateType>()->
values, *joint_bounds_,
272 state->as<
StateType>()->clearKnownInformation();
275 void sampleGaussian(ompl::base::State* state,
const ompl::base::State* mean,
const double stdDev)
override
277 sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
286 return ompl::base::StateSamplerPtr(
static_cast<ompl::base::StateSampler*
>(
287 new DefaultStateSampler(
this, spec_.joint_model_group_, &spec_.joint_bounds_)));
292 out <<
"ModelBasedStateSpace '" <<
getName() <<
"' at " <<
this << std::endl;
299 out << j->getName() <<
" = ";
300 const int idx = spec_.joint_model_group_->getVariableGroupIndex(j->getName());
301 const int vc = j->getVariableCount();
302 for (
int i = 0; i < vc; ++i)
308 out <<
"* start state" << std::endl;
310 out <<
"* goal state" << std::endl;
314 out <<
"* valid state" << std::endl;
316 out <<
"* invalid state" << std::endl;
318 out <<
"Tag: " << state->as<
StateType>()->tag << std::endl;
322 const ompl::base::State* state)
const
333 state->as<
StateType>()->clearKnownInformation();
339 int ompl_state_joint_index)
const
342 memcpy(getValueAddressAtIndex(state, ompl_state_joint_index),
347 state->as<
StateType>()->clearKnownInformation();