moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
cost_functions.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, PickNik 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 PickNik Inc. 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
40#pragma once
41
42#include <Eigen/Geometry>
43
46
49
50namespace stomp_moveit
51{
52// Validates a given state and produces a scalar cost penalty - example use cases are collision or constraint checking
53using StateValidatorFn = std::function<double(const Eigen::VectorXd& state_positions)>;
54
55namespace costs
56{
57
58// Interpolation step size for collision checking (joint space, L2 norm)
59constexpr double COL_CHECK_DISTANCE = 0.05;
60constexpr double CONSTRAINT_CHECK_DISTANCE = 0.05;
61
76CostFn getCostFunctionFromStateValidator(const StateValidatorFn& state_validator_fn, double interpolation_step_size)
77{
78 CostFn cost_fn = [=](const Eigen::MatrixXd& values, Eigen::VectorXd& costs, bool& validity) {
79 // Assume zero cost and valid trajectory from the start
80 costs.setZero(values.cols());
81 validity = true;
82
83 // Iterate over sample waypoint pairs and check for validity in each segment.
84 // If an invalid state is found, weighted penalty costs are applied to both waypoints.
85 // Subsequent invalid states are assumed to have the same cause, so we are keeping track
86 // of "invalid windows" which are used for smoothing out the costs per violation cause
87 // with a gaussian, penalizing neighboring valid states as well.
88 // Invalid windows are represented as pairs of start and end timesteps.
89 std::vector<std::pair<long, long>> invalid_windows;
90 bool in_invalid_window = false;
91 for (int timestep = 0; timestep < values.cols(); ++timestep)
92 {
93 // Get state at current timestep and check for validity
94 // The penalty of the validation function is added to the cost of the current timestep
95 // A state is rendered invalid if a cost results from the current validity check or if a penalty is carried over
96 // from the previous iteration.
97 Eigen::VectorXd current = values.col(timestep);
98 costs(timestep) += state_validator_fn(current);
99 bool found_invalid_state = costs(timestep) > 0.0;
100
101 // If state is valid, interpolate towards the next waypoint if there is one
102 bool continue_interpolation =
103 !found_invalid_state && timestep < (values.cols() - 1) && interpolation_step_size > 0.0;
104 if (continue_interpolation)
105 {
106 Eigen::VectorXd next = values.col(timestep + 1);
107 // Interpolate waypoints at least once, even if interpolation_step_size exceeds the waypoint distance
108 const double interpolation_step = std::min(0.5, interpolation_step_size / (next - current).norm());
109 for (double interpolation_fraction = interpolation_step; interpolation_fraction < 1.0;
110 interpolation_fraction += interpolation_step)
111 {
112 Eigen::VectorXd sample_vec = (1 - interpolation_fraction) * current + interpolation_fraction * next;
113
114 double penalty = state_validator_fn(sample_vec);
115 found_invalid_state = penalty > 0.0;
116 if (found_invalid_state)
117 {
118 // Apply weighted penalties -> This trajectory is definitely invalid
119 costs(timestep) += (1 - interpolation_fraction) * penalty;
120 costs(timestep + 1) += interpolation_fraction * penalty;
121 break;
122 }
123 }
124 }
125
126 // Track groups of invalid states as "invalid windows" for subsequent smoothing
127 if (found_invalid_state)
128 {
129 // Mark solution as invalid
130 validity = false;
131
132 // OPEN new invalid window when this is the first detected invalid state in a group
133 if (!in_invalid_window)
134 {
135 // new windows only include a single timestep as start and end state
136 invalid_windows.emplace_back(timestep, timestep);
137 in_invalid_window = true;
138 }
139
140 // Update end of invalid window with the current invalid timestep
141 invalid_windows.back().second = timestep;
142 }
143 else
144 {
145 // CLOSE current invalid window if the current state is valid
146 in_invalid_window = false;
147 }
148 }
149
150 // Smooth out cost of invalid segments using a gaussian
151 // The standard deviation is picked so that neighboring states
152 // before and after the violation are penalized as well.
153 for (const auto& [start, end] : invalid_windows)
154 {
155 // Total cost of invalid states
156 // We are smoothing the exact same total cost over a wider neighborhood
157 const double window_cost = costs(Eigen::seq(start, end)).sum();
158
159 // window size defines 2 sigma of gaussian smoothing kernel
160 // which equals 68.2% of overall cost and about 25% of width
161 const double window_size = static_cast<double>(end - start) + 1;
162 const double sigma = std::max(1.0, 0.5 * window_size);
163 const double mu = 0.5 * (start + end);
164
165 // Iterate over waypoints in the range of +/-sigma (neighborhood)
166 // and add a discrete cost value for each waypoint based on a Gaussian
167 // distribution.
168 const long kernel_start = mu - static_cast<long>(sigma) * 4;
169 const long kernel_end = mu + static_cast<long>(sigma) * 4;
170 const long bounded_kernel_start = std::max(0l, kernel_start);
171 const long bounded_kernel_end = std::min(values.cols() - 1, kernel_end);
172 for (auto j = bounded_kernel_start; j <= bounded_kernel_end; ++j)
173 {
174 costs(j) = std::exp(-std::pow(j - mu, 2) / (2 * std::pow(sigma, 2))) / (sigma * std::sqrt(2 * M_PI));
175 }
176
177 // Normalize values to original total window cost
178 const double cost_sum = costs(Eigen::seq(bounded_kernel_start, bounded_kernel_end)).sum();
179 costs(Eigen::seq(bounded_kernel_start, bounded_kernel_end)) *= window_cost / cost_sum;
180 }
181
182 return true;
183 };
184
185 return cost_fn;
186}
187
199CostFn getCollisionCostFunction(const std::shared_ptr<const planning_scene::PlanningScene>& planning_scene,
200 const moveit::core::JointModelGroup* group, double collision_penalty)
201{
202 const auto& joints = group ? group->getActiveJointModels() : planning_scene->getRobotModel()->getActiveJointModels();
203 const auto& group_name = group ? group->getName() : "";
204
205 StateValidatorFn collision_validator_fn = [=](const Eigen::VectorXd& positions) {
206 static moveit::core::RobotState state(planning_scene->getCurrentState());
207
208 // Update robot state values
209 setJointPositions(positions, joints, state);
210 state.update();
211
212 return planning_scene->isStateColliding(state, group_name) ? collision_penalty : 0.0;
213 };
214
215 return getCostFunctionFromStateValidator(collision_validator_fn, COL_CHECK_DISTANCE);
216}
217
230CostFn getConstraintsCostFunction(const std::shared_ptr<const planning_scene::PlanningScene>& planning_scene,
232 const moveit_msgs::msg::Constraints& constraints_msg, double cost_scale)
233{
234 const auto& joints = group ? group->getActiveJointModels() : planning_scene->getRobotModel()->getActiveJointModels();
235
237 constraints.add(constraints_msg, planning_scene->getTransforms());
238
239 StateValidatorFn constraints_validator_fn = [=](const Eigen::VectorXd& positions) {
240 static moveit::core::RobotState state(planning_scene->getCurrentState());
241
242 // Update robot state values
243 setJointPositions(positions, joints, state);
244 state.update();
245
246 return constraints.decide(state).distance * cost_scale;
247 };
248
249 return getCostFunctionFromStateValidator(constraints_validator_fn, CONSTRAINT_CHECK_DISTANCE);
250}
251
259CostFn sum(const std::vector<CostFn>& cost_functions)
260{
261 return [=](const Eigen::MatrixXd& values, Eigen::VectorXd& overall_costs, bool& overall_validity) {
262 overall_validity = true;
263 overall_costs.setZero(values.cols());
264
265 auto costs = overall_costs;
266 for (const auto& cost_fn : cost_functions)
267 {
268 bool valid = true;
269 cost_fn(values, costs, valid);
270
271 // Sum results
272 overall_validity = overall_validity && valid;
273 overall_costs += costs;
274 }
275 return true;
276 };
277}
278} // namespace costs
279} // namespace stomp_moveit
A class that contains many different constraints, and can check RobotState *versus the full set....
bool add(const moveit_msgs::msg::Constraints &c, const moveit::core::Transforms &tf)
Add all known constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
const std::string & getName() const
Get the name of the joint group.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void update(bool force=false)
Update all transforms.
Helper functions for converting between MoveIt types and plain Eigen types.
This namespace includes the central class for representing planning contexts.
CostFn getCostFunctionFromStateValidator(const StateValidatorFn &state_validator_fn, double interpolation_step_size)
CostFn getConstraintsCostFunction(const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group, const moveit_msgs::msg::Constraints &constraints_msg, double cost_scale)
constexpr double COL_CHECK_DISTANCE
CostFn sum(const std::vector< CostFn > &cost_functions)
constexpr double CONSTRAINT_CHECK_DISTANCE
CostFn getCollisionCostFunction(const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group, double collision_penalty)
void setJointPositions(const Eigen::VectorXd &values, const Joints &joints, moveit::core::RobotState &state)
std::function< bool(const Eigen::MatrixXd &values, Eigen::VectorXd &costs, bool &validity)> CostFn
std::function< double(const Eigen::VectorXd &state_positions)> StateValidatorFn
A STOMP task definition that allows injecting custom functions for planning.
double distance
The distance evaluation from the constraint or constraints.