moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
state_validity_checker.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, 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, Jeroen De Maeyer */
36
39#include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
43
44namespace ompl_interface
45{
46namespace
47{
48rclcpp::Logger getLogger()
49{
50 return moveit::getLogger("moveit.planners.ompl.state_validity_checker");
51}
52} // namespace
53
55 : ompl::base::StateValidityChecker(pc->getOMPLSimpleSetup()->getSpaceInformation())
56 , planning_context_(pc)
57 , group_name_(pc->getGroupName())
58 , tss_(pc->getCompleteInitialRobotState())
59 , verbose_(false)
60{
61 specs_.clearanceComputationType = ompl::base::StateValidityCheckerSpecs::APPROXIMATE;
62 specs_.hasValidDirectionComputation = false;
63
66
70
73
76}
77
79{
80 verbose_ = flag;
83bool StateValidityChecker::isValid(const ompl::base::State* state, bool verbose) const
84{
85 assert(state != nullptr);
86 // Use cached validity if it is available
88 {
89 return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
90 }
91
92 if (!si_->satisfiesBounds(state))
93 {
94 if (verbose)
95 {
96 RCLCPP_INFO(getLogger(), "State outside bounds");
97 }
98 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
99 return false;
100 }
101
103 planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
104
105 // check path constraints
106 const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
107 if (kset && !kset->decide(*robot_state, verbose).satisfied)
108 {
109 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
110 return false;
111 }
112
113 // check feasibility
114 if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
115 {
116 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
117 return false;
118 }
119
120 // check collision avoidance
122 planning_context_->getPlanningScene()->checkCollision(
123 verbose ? collision_request_simple_verbose_ : collision_request_simple_, res, *robot_state);
124 if (!res.collision)
125 {
126 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
127 }
128 else
129 {
130 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
131 }
132 return !res.collision;
133}
134
135bool StateValidityChecker::isValid(const ompl::base::State* state, double& dist, bool verbose) const
136{
137 assert(state != nullptr);
138 // Use cached validity and distance if they are available
141 {
142 dist = state->as<ModelBasedStateSpace::StateType>()->distance;
143 return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
144 }
145
146 if (!si_->satisfiesBounds(state))
147 {
148 if (verbose)
149 {
150 RCLCPP_INFO(getLogger(), "State outside bounds");
151 }
152 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
153 return false;
154 }
155
157 planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
158
159 // check path constraints
160 const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
161 if (kset)
162 {
163 kinematic_constraints::ConstraintEvaluationResult cer = kset->decide(*robot_state, verbose);
164 if (!cer.satisfied)
165 {
166 dist = cer.distance;
167 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(dist);
168 return false;
169 }
170 }
171
172 // check feasibility
173 if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
174 {
175 dist = 0.0;
176 return false;
177 }
178
179 // check collision avoidance
181 planning_context_->getPlanningScene()->checkCollision(
183 dist = res.distance;
184 return !res.collision;
185}
186
187double StateValidityChecker::cost(const ompl::base::State* state) const
188{
189 assert(state != nullptr);
190 double cost = 0.0;
191
193 planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
194
195 // Calculates cost from a summation of distance to obstacles times the size of the obstacle
197 planning_context_->getPlanningScene()->checkCollision(collision_request_with_cost_, res, *robot_state);
198
199 for (const collision_detection::CostSource& cost_source : res.cost_sources)
200 {
201 cost += cost_source.cost * cost_source.getVolume();
202 }
203
204 return cost;
205}
206
207double StateValidityChecker::clearance(const ompl::base::State* state) const
208{
209 assert(state != nullptr);
211 planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
212
214 planning_context_->getPlanningScene()->checkCollision(collision_request_with_distance_, res, *robot_state);
215 return res.collision ? 0.0 : (res.distance < 0.0 ? std::numeric_limits<double>::infinity() : res.distance);
216}
217
218/*******************************************
219 * Constrained Planning StateValidityChecker
220 * *****************************************/
221bool ConstrainedPlanningStateValidityChecker::isValid(const ompl::base::State* wrapped_state, bool verbose) const
222{
223 assert(wrapped_state != nullptr);
224 // Unwrap the state from a ConstrainedStateSpace::StateType
225 auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
226
227 // Use cached validity if it is available
229 {
230 return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
231 }
232
233 // do not use the unwrapped state here, as satisfiesBounds expects a state of type ConstrainedStateSpace::StateType
234 if (!si_->satisfiesBounds(wrapped_state)) // si_ = ompl::base::SpaceInformation
235 {
236 RCLCPP_DEBUG(getLogger(), "State outside bounds");
237 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
238 return false;
239 }
240
242 // do not use the unwrapped state here, as copyToRobotState expects a state of type ConstrainedStateSpace::StateType
243 planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, wrapped_state);
244
245 // check path constraints
246 const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
247 if (kset && !kset->decide(*robot_state, verbose).satisfied)
248 {
249 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
250 return false;
251 }
252
253 // check feasibility
254 if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
255 {
256 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
257 return false;
258 }
259
260 // check collision avoidance
262 planning_context_->getPlanningScene()->checkCollision(
263 verbose ? collision_request_simple_verbose_ : collision_request_simple_, res, *robot_state);
264 if (!res.collision)
265 {
266 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
267 }
268 else
269 {
270 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
271 }
272 return !res.collision;
273}
274
275bool ConstrainedPlanningStateValidityChecker::isValid(const ompl::base::State* wrapped_state, double& dist,
276 bool verbose) const
277{
278 assert(wrapped_state != nullptr);
279 // Unwrap the state from a ConstrainedStateSpace::StateType
280 auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
281
282 // Use cached validity and distance if they are available
285 {
286 dist = state->as<ModelBasedStateSpace::StateType>()->distance;
287 return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
288 }
289
290 // do not use the unwrapped state here, as satisfiesBounds expects a state of type ConstrainedStateSpace::StateType
291 if (!si_->satisfiesBounds(wrapped_state)) // si_ = ompl::base::SpaceInformation
292 {
293 RCLCPP_DEBUG(getLogger(), "State outside bounds");
294 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
295 return false;
296 }
297
299
300 // do not use the unwrapped state here, as copyToRobotState expects a state of type ConstrainedStateSpace::StateType
301 planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, wrapped_state);
302
303 // check path constraints
304 const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
305 if (kset && !kset->decide(*robot_state, verbose).satisfied)
306 {
307 const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
308 return false;
309 }
310
311 // check feasibility
312 if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
313 {
314 dist = 0.0;
315 return false;
316 }
317
318 // check collision avoidance
320 planning_context_->getPlanningScene()->checkCollision(
322 dist = res.distance;
323 return !res.collision;
324}
325} // namespace ompl_interface
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
bool isValid(const ompl::base::State *wrapped_state, bool verbose) const override
Check validity for states of type ompl::base::ConstrainedStateSpace.
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
An interface for a OMPL state validity checker.
collision_detection::CollisionRequest collision_request_simple_
StateValidityChecker(const ModelBasedPlanningContext *planning_context)
const ModelBasedPlanningContext * planning_context_
double clearance(const ompl::base::State *state) const override
virtual double cost(const ompl::base::State *state) const
bool isValid(const ompl::base::State *state) const override
collision_detection::CollisionRequest collision_request_with_distance_
collision_detection::CollisionRequest collision_request_with_cost_
collision_detection::CollisionRequest collision_request_with_distance_verbose_
collision_detection::CollisionRequest collision_request_simple_verbose_
moveit::core::RobotState * getStateStorage() const
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
The MoveIt interface to OMPL.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool cost
If true, a collision cost is computed.
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
double distance
Closest distance between two bodies.
bool collision
True if collision was found, false otherwise.
When collision costs are computed, this structure contains information about the partial cost incurre...
Struct for containing the results of constraint evaluation.
bool satisfied
Whether or not the constraint or constraints were satisfied.
double distance
The distance evaluation from the constraint or constraints.
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)