moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
model_based_state_space.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
38#include <utility>
40
41namespace ompl_interface
42{
43namespace
44{
45rclcpp::Logger getLogger()
46{
47 return moveit::getLogger("moveit.planners.ompl.model_based_state_space");
48}
49} // namespace
50
52 : ompl::base::StateSpace(), spec_(std::move(spec))
53{
54 // set the state space name
57 state_values_size_ = variable_count_ * sizeof(double);
59
60 // make sure we have bounds for every joint stored within the spec (use default bounds if not specified)
61 if (!spec_.joint_bounds_.empty() && spec_.joint_bounds_.size() != joint_model_vector_.size())
62 {
63 RCLCPP_ERROR(getLogger(), "Joint group '%s' has incorrect bounds specified. Using the default bounds instead.",
65 spec_.joint_bounds_.clear();
66 }
67
68 // copy the default joint bounds if needed
69 if (spec_.joint_bounds_.empty())
71
72 // new perform a deep copy of the bounds, in case we need to modify them
74 for (std::size_t i = 0; i < joint_bounds_storage_.size(); ++i)
75 {
78 }
79
80 // default settings
82
84 params_.declareParam<double>(
85 "tag_snap_to_segment", [this](double tag_snap_to_segment) { setTagSnapToSegment(tag_snap_to_segment); },
86 [this] { return getTagSnapToSegment(); });
87}
88
90
95
97{
98 if (snap < 0.0 || snap > 1.0)
99 {
100 RCLCPP_WARN(getLogger(),
101 "Snap to segment for tags is a ratio. It's value must be between 0.0 and 1.0. "
102 "Value remains as previously set (%lf)",
104 }
105 else
106 {
109 }
110}
111
112ompl::base::State* ModelBasedStateSpace::allocState() const
113{
114 auto* state = new StateType();
115 state->values = new double[variable_count_];
116 return state;
117}
118
119void ModelBasedStateSpace::freeState(ompl::base::State* state) const
120{
121 delete[] state->as<StateType>()->values;
122 delete state->as<StateType>();
123}
124
125void ModelBasedStateSpace::copyState(ompl::base::State* destination, const ompl::base::State* source) const
126{
127 memcpy(destination->as<StateType>()->values, source->as<StateType>()->values, state_values_size_);
128 destination->as<StateType>()->tag = source->as<StateType>()->tag;
129 destination->as<StateType>()->flags = source->as<StateType>()->flags;
130 destination->as<StateType>()->distance = source->as<StateType>()->distance;
131}
132
134{
135 return state_values_size_ + sizeof(int);
136}
137
138void ModelBasedStateSpace::serialize(void* serialization, const ompl::base::State* state) const
139{
140 *reinterpret_cast<int*>(serialization) = state->as<StateType>()->tag;
141 memcpy(reinterpret_cast<char*>(serialization) + sizeof(int), state->as<StateType>()->values, state_values_size_);
142}
143
144void ModelBasedStateSpace::deserialize(ompl::base::State* state, const void* serialization) const
145{
146 state->as<StateType>()->tag = *reinterpret_cast<const int*>(serialization);
147 memcpy(state->as<StateType>()->values, reinterpret_cast<const char*>(serialization) + sizeof(int), state_values_size_);
148}
149
151{
152 unsigned int d = 0;
154 d += i->getStateSpaceDimension();
155 return d;
156}
157
162
164{
165 double m = 1.0;
167 {
168 for (const moveit::core::VariableBounds& bound : *bounds)
169 {
170 m *= bound.max_position_ - bound.min_position_;
171 }
172 }
173 return m;
174}
175
176double ModelBasedStateSpace::distance(const ompl::base::State* state1, const ompl::base::State* state2) const
177{
179 {
180 return distance_function_(state1, state2);
181 }
182 else
183 {
184 return spec_.joint_model_group_->distance(state1->as<StateType>()->values, state2->as<StateType>()->values);
185 }
186}
187
188bool ModelBasedStateSpace::equalStates(const ompl::base::State* state1, const ompl::base::State* state2) const
189{
190 for (unsigned int i = 0; i < variable_count_; ++i)
191 {
192 if (fabs(state1->as<StateType>()->values[i] - state2->as<StateType>()->values[i]) >
193 std::numeric_limits<double>::epsilon())
194 return false;
195 }
196 return true;
197}
198
203
204bool ModelBasedStateSpace::satisfiesBounds(const ompl::base::State* state) const
205{
207 std::numeric_limits<double>::epsilon());
208}
209
210void ModelBasedStateSpace::interpolate(const ompl::base::State* from, const ompl::base::State* to, const double t,
211 ompl::base::State* state) const
212{
213 // clear any cached info (such as validity known or not)
214 state->as<StateType>()->clearKnownInformation();
215
216 if (!interpolation_function_ || !interpolation_function_(from, to, t, state))
217 {
218 // perform the actual interpolation
220 state->as<StateType>()->values);
221
222 // compute tag
223 if (from->as<StateType>()->tag >= 0 && t < 1.0 - tag_snap_to_segment_)
224 {
225 state->as<StateType>()->tag = from->as<StateType>()->tag;
226 }
227 else if (to->as<StateType>()->tag >= 0 && t > tag_snap_to_segment_)
228 {
229 state->as<StateType>()->tag = to->as<StateType>()->tag;
230 }
231 else
232 {
233 state->as<StateType>()->tag = -1;
234 }
235 }
236}
237
238double* ModelBasedStateSpace::getValueAddressAtIndex(ompl::base::State* state, const unsigned int index) const
239{
240 if (index >= variable_count_)
241 return nullptr;
242 return state->as<StateType>()->values + index;
243}
244
245void ModelBasedStateSpace::setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ,
246 double maxZ)
247{
248 for (std::size_t i = 0; i < joint_model_vector_.size(); ++i)
249 {
251 {
252 joint_bounds_storage_[i][0].min_position_ = minX;
253 joint_bounds_storage_[i][0].max_position_ = maxX;
254 joint_bounds_storage_[i][1].min_position_ = minY;
255 joint_bounds_storage_[i][1].max_position_ = maxY;
256 }
258 {
259 joint_bounds_storage_[i][0].min_position_ = minX;
260 joint_bounds_storage_[i][0].max_position_ = maxX;
261 joint_bounds_storage_[i][1].min_position_ = minY;
262 joint_bounds_storage_[i][1].max_position_ = maxY;
263 joint_bounds_storage_[i][2].min_position_ = minZ;
264 joint_bounds_storage_[i][2].max_position_ = maxZ;
265 }
266 }
267}
268
269ompl::base::StateSamplerPtr ModelBasedStateSpace::allocDefaultStateSampler() const
270{
271 class DefaultStateSampler : public ompl::base::StateSampler
272 {
273 public:
274 DefaultStateSampler(const ompl::base::StateSpace* space, const moveit::core::JointModelGroup* group,
275 const moveit::core::JointBoundsVector* joint_bounds)
276 : ompl::base::StateSampler(space), joint_model_group_(group), joint_bounds_(joint_bounds)
277 {
278 }
279
280 void sampleUniform(ompl::base::State* state) override
281 {
282 joint_model_group_->getVariableRandomPositions(moveit_rng_, state->as<StateType>()->values, *joint_bounds_);
283 state->as<StateType>()->clearKnownInformation();
284 }
285
286 void sampleUniformNear(ompl::base::State* state, const ompl::base::State* near, const double distance) override
287 {
288 joint_model_group_->getVariableRandomPositionsNearBy(moveit_rng_, state->as<StateType>()->values, *joint_bounds_,
289 near->as<StateType>()->values, distance);
290 state->as<StateType>()->clearKnownInformation();
291 }
292
293 void sampleGaussian(ompl::base::State* state, const ompl::base::State* mean, const double stdDev) override
294 {
295 sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
296 }
297
298 protected:
299 random_numbers::RandomNumberGenerator moveit_rng_;
300 const moveit::core::JointModelGroup* joint_model_group_;
301 const moveit::core::JointBoundsVector* joint_bounds_;
302 };
303
304 return ompl::base::StateSamplerPtr(static_cast<ompl::base::StateSampler*>(
305 new DefaultStateSampler(this, spec_.joint_model_group_, &spec_.joint_bounds_)));
306}
307
308void ModelBasedStateSpace::printSettings(std::ostream& out) const
309{
310 out << "ModelBasedStateSpace '" << getName() << "' at " << this << '\n';
311}
312
313void ModelBasedStateSpace::printState(const ompl::base::State* state, std::ostream& out) const
314{
316 {
317 out << j->getName() << " = ";
318 const int idx = spec_.joint_model_group_->getVariableGroupIndex(j->getName());
319 const int vc = j->getVariableCount();
320 for (int i = 0; i < vc; ++i)
321 out << state->as<StateType>()->values[idx + i] << ' ';
322 out << '\n';
323 }
324
325 if (state->as<StateType>()->isStartState())
326 out << "* start state \n";
327 if (state->as<StateType>()->isGoalState())
328 out << "* goal state \n";
329 if (state->as<StateType>()->isValidityKnown())
330 {
331 if (state->as<StateType>()->isMarkedValid())
332 {
333 out << "* valid state \n";
334 }
335 else
336 {
337 out << "* invalid state \n";
338 }
339 }
340 out << "Tag: " << state->as<StateType>()->tag << '\n';
341}
342
343void ModelBasedStateSpace::copyToRobotState(moveit::core::RobotState& rstate, const ompl::base::State* state) const
344{
346 rstate.update();
347}
348
349void ModelBasedStateSpace::copyToOMPLState(ompl::base::State* state, const moveit::core::RobotState& rstate) const
350{
352 // clear any cached info (such as validity known or not)
353 state->as<StateType>()->clearKnownInformation();
354}
355
356void ModelBasedStateSpace::copyJointToOMPLState(ompl::base::State* state, const moveit::core::RobotState& robot_state,
357 const moveit::core::JointModel* joint_model,
358 int ompl_state_joint_index) const
359{
360 // Copy one joint (multiple variables possibly)
361 memcpy(getValueAddressAtIndex(state, ompl_state_joint_index),
362 robot_state.getVariablePositions() + joint_model->getFirstVariableIndex(),
363 joint_model->getVariableCount() * sizeof(double));
364
365 // clear any cached info (such as validity known or not)
366 state->as<StateType>()->clearKnownInformation();
367}
368
369} // namespace ompl_interface
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
double distance(const double *state1, const double *state2) const
const std::string & getName() const
Get the name of the joint group.
bool enforcePositionBounds(double *state) const
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
void interpolate(const double *from, const double *to, double t, double *state) const
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
void update(bool force=false)
Update all transforms.
bool satisfiesBounds(const ompl::base::State *state) 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...
bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const override
void serialize(void *serialization, const ompl::base::State *state) const override
double * getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const override
std::vector< const moveit::core::JointModel * > joint_model_vector_
void deserialize(ompl::base::State *state, const void *serialization) const override
std::vector< moveit::core::JointModel::Bounds > joint_bounds_storage_
ModelBasedStateSpaceSpecification spec_
unsigned int getSerializationLength() const override
ompl::base::State * allocState() 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.
ompl::base::StateSamplerPtr allocDefaultStateSampler() 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.
void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const override
void printState(const ompl::base::State *state, std::ostream &out) const override
ModelBasedStateSpace(ModelBasedStateSpaceSpecification spec)
void freeState(ompl::base::State *state) const override
void copyState(ompl::base::State *destination, const ompl::base::State *source) const override
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.
void printSettings(std::ostream &out) const override
void enforceBounds(ompl::base::State *state) const override
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
std::vector< const JointModel::Bounds * > JointBoundsVector
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
The MoveIt interface to OMPL.
const moveit::core::JointModelGroup * joint_model_group_