moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
stomp_moveit_planning_context.cpp
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
39#include <atomic>
40#include <future>
41
42#include <stomp/stomp.h>
43
50#include <stomp_moveit_parameters.hpp>
51
55
56namespace stomp_moveit
57{
58namespace
59{
60rclcpp::Logger getLogger()
61{
62 return moveit::getLogger("moveit.planners.stomp.planning_context");
63}
64} // namespace
65
66// @brief Run a planning attempt with STOMP, either providing start and goal states or an optional seed trajectory
67bool solveWithStomp(const std::shared_ptr<stomp::Stomp>& stomp, const moveit::core::RobotState& start_state,
68 const moveit::core::RobotState& goal_state, const moveit::core::JointModelGroup* group,
69 const robot_trajectory::RobotTrajectoryPtr& input_trajectory,
70 robot_trajectory::RobotTrajectoryPtr& output_trajectory)
71{
72 Eigen::MatrixXd waypoints;
73 const auto& joints = group->getActiveJointModels();
74 bool success = false;
75 if (!input_trajectory || input_trajectory->empty())
76 {
77 success = stomp->solve(getPositions(start_state, joints), getPositions(goal_state, joints), waypoints);
78 }
79 else
80 {
81 auto input = robotTrajectoryToMatrix(*input_trajectory);
82 success = stomp->solve(input, waypoints);
83 }
84 if (success)
85 {
86 output_trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(start_state.getRobotModel(), group);
87 fillRobotTrajectory(waypoints, start_state, *output_trajectory);
88 }
89
90 return success;
91}
92
93// @brief Extract a robot trajectory from the seed waypoints passed with a motion plan request
95 const moveit::core::RobotModelConstPtr& robot_model,
96 robot_trajectory::RobotTrajectoryPtr& seed)
97{
98 if (req.trajectory_constraints.constraints.empty())
99 {
100 return false;
101 }
102
103 const auto* joint_group = robot_model->getJointModelGroup(req.group_name);
104 const auto& names = joint_group->getActiveJointModelNames();
105 const auto dof = names.size();
106
107 trajectory_msgs::msg::JointTrajectory seed_traj;
108 const auto& constraints = req.trajectory_constraints.constraints; // alias to keep names short
109 // Test the first point to ensure that it has all of the joints required
110 for (size_t i = 0; i < constraints.size(); ++i)
111 {
112 auto n = constraints[i].joint_constraints.size();
113 if (n != dof)
114 { // first test to ensure that dimensionality is correct
115 RCLCPP_WARN(getLogger(), "Seed trajectory index %lu does not have %lu constraints (has %lu instead).", i, dof, n);
116 return false;
117 }
118
119 trajectory_msgs::msg::JointTrajectoryPoint joint_pt;
120
121 for (size_t j = 0; j < constraints[i].joint_constraints.size(); ++j)
122 {
123 const auto& c = constraints[i].joint_constraints[j];
124 if (c.joint_name != names[j])
125 {
126 RCLCPP_WARN(getLogger(),
127 "Seed trajectory (index %lu, joint %lu) joint name '%s' does not match expected name '%s'", i, j,
128 c.joint_name.c_str(), names[j].c_str());
129 return false;
130 }
131 joint_pt.positions.push_back(c.position);
132 }
133
134 seed_traj.points.push_back(joint_pt);
135 }
136 seed_traj.joint_names = names;
137
138 moveit::core::RobotState robot_state(robot_model);
139 moveit::core::robotStateMsgToRobotState(req.start_state, robot_state);
140 seed = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model, joint_group);
141 seed->setRobotTrajectoryMsg(robot_state, seed_traj);
142
143 return !seed->empty();
144}
145
146// @brief Build a STOMP task that uses MoveIt callback types for planning in STOMP
147stomp::TaskPtr createStompTask(const stomp::StompConfiguration& config, StompPlanningContext& context)
148{
149 const size_t num_timesteps = config.num_timesteps;
150 const auto planning_scene = context.getPlanningScene();
151 const auto group = planning_scene->getRobotModel()->getJointModelGroup(context.getGroupName());
152
153 // Check if we do have path constraints
154 const auto& req = context.getMotionPlanRequest();
156 constraints.add(req.path_constraints, planning_scene->getTransforms());
157
158 // Create callback functions for STOMP task
159 // Cost, noise and filter functions are provided for planning.
160 // TODO(henningkayser): parameterize cost penalties
161 using namespace stomp_moveit;
162 CostFn cost_fn;
163 if (!constraints.empty())
164 {
165 cost_fn = costs::sum({ costs::getCollisionCostFunction(planning_scene, group, 1.0 /* collision penalty */),
167 1.0 /* constraint penalty */) });
168 }
169 else
170 {
171 cost_fn = costs::getCollisionCostFunction(planning_scene, group, 1.0 /* collision penalty */);
172 }
173
174 // TODO(henningkayser): parameterize stddev
175 const std::vector<double> stddev(group->getActiveJointModels().size(), 0.1);
176 auto noise_generator_fn = noise::getNormalDistributionGenerator(num_timesteps, stddev);
177 auto filter_fn =
179 auto iteration_callback_fn =
181 auto done_callback_fn =
183
184 // Initialize and return STOMP task
185 stomp::TaskPtr task =
186 std::make_shared<ComposableTask>(noise_generator_fn, cost_fn, filter_fn, iteration_callback_fn, done_callback_fn);
187 return task;
188}
189
190// @brief Create a valid STOMP configuration from runtime parameters and dimensions provided by the planning request
191stomp::StompConfiguration getStompConfig(const stomp_moveit::Params& params, size_t num_dimensions)
192{
193 stomp::StompConfiguration config;
194 config.num_dimensions = num_dimensions; // Copied from joint count
195 // TODO(henningkayser): set from request or params
196 config.initialization_method = stomp::TrajectoryInitializations::LINEAR_INTERPOLATION;
197 config.num_iterations = params.num_iterations;
198 config.num_iterations_after_valid = params.num_iterations_after_valid;
199 config.num_timesteps = params.num_timesteps;
200 config.delta_t = params.delta_t;
201 config.exponentiated_cost_sensitivity = params.exponentiated_cost_sensitivity;
202 config.num_rollouts = params.num_rollouts;
203 config.max_rollouts = params.max_rollouts;
204 config.control_cost_weight = params.control_cost_weight;
205
206 return config;
207}
208
209StompPlanningContext::StompPlanningContext(const std::string& name, const std::string& group,
210 const stomp_moveit::Params& params)
211 : planning_interface::PlanningContext(name, group), params_(params)
212{
213}
214
216{
217 // Start time
218 auto time_start = std::chrono::steady_clock::now();
219
220 res.planner_id = std::string("stomp");
221 // Default to happy path
222 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
223
224 // Extract start and goal states
225 const auto& req = getMotionPlanRequest();
226 const moveit::core::RobotState start_state(*getPlanningScene()->getCurrentStateUpdated(req.start_state));
227 moveit::core::RobotState goal_state(start_state);
229 auto goal_sampler = sampler_manager.selectSampler(getPlanningScene(), getGroupName(), req.goal_constraints.at(0));
230 if (!goal_sampler || !goal_sampler->sample(goal_state))
231 {
232 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
233 return; // Can't plan without valid goal state
234 }
235
236 // STOMP config, task, planner instance
237 const auto group = getPlanningScene()->getRobotModel()->getJointModelGroup(getGroupName());
238 auto config = getStompConfig(params_, group->getActiveJointModels().size() /* num_dimensions */);
239 robot_trajectory::RobotTrajectoryPtr input_trajectory;
240 if (extractSeedTrajectory(request_, getPlanningScene()->getRobotModel(), input_trajectory))
241 {
242 config.num_timesteps = input_trajectory->size();
243 }
244 const auto task = createStompTask(config, *this);
245 stomp_ = std::make_shared<stomp::Stomp>(config, task);
246
247 std::condition_variable cv;
248 std::mutex cv_mutex;
249 bool finished = false;
250 auto timeout_future = std::async(std::launch::async, [&, stomp = stomp_]() {
251 std::unique_lock<std::mutex> lock(cv_mutex);
252 cv.wait_for(lock, std::chrono::duration<double>(req.allowed_planning_time), [&finished] { return finished; });
253 if (!finished)
254 {
255 stomp->cancel();
256 }
257 });
258
259 // Solve
260 if (!solveWithStomp(stomp_, start_state, goal_state, group, input_trajectory, res.trajectory))
261 {
262 // We timed out if the timeout task has completed so that the timeout future is valid and ready
263 bool timed_out =
264 timeout_future.valid() && timeout_future.wait_for(std::chrono::nanoseconds(1)) == std::future_status::ready;
265 res.error_code.val =
266 timed_out ? moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT : moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
267 }
268 stomp_.reset();
269 {
270 std::unique_lock<std::mutex> lock(cv_mutex);
271 finished = true;
272 cv.notify_all();
273 }
274
275 // Stop time
276 std::chrono::duration<double> elapsed_seconds = std::chrono::steady_clock::now() - time_start;
277 res.planning_time = elapsed_seconds.count();
278}
279
281{
282 // TODO(#2168): implement this function
283 RCLCPP_ERROR(getLogger(),
284 "StompPlanningContext::solve(planning_interface::MotionPlanDetailedResponse&) is not implemented!");
285 return;
286}
287
289{
290 // Copy shared pointer to avoid race conditions
291 auto stomp = stomp_;
292 if (stomp)
293 {
294 return stomp->cancel();
295 }
296
297 return true;
298}
299
303
305 const std::shared_ptr<rclcpp::Publisher<visualization_msgs::msg::MarkerArray>>& path_publisher)
306{
307 path_publisher_ = path_publisher;
308}
309
310std::shared_ptr<rclcpp::Publisher<visualization_msgs::msg::MarkerArray>> StompPlanningContext::getPathPublisher()
311{
312 return path_publisher_;
313}
314} // namespace stomp_moveit
This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs...
ConstraintSamplerPtr selectSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::msg::Constraints &constr) const
Selects among the potential sampler allocators.
A class that contains many different constraints, and can check RobotState *versus the full set....
bool empty() const
Returns whether or not there are any constraints in the set.
bool add(const moveit_msgs::msg::Constraints &c, const moveit::core::Transforms &tf)
Add all known constraints.
const moveit_msgs::msg::Constraints & getAllConstraints() const
Get all constraints in the set.
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
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Representation of a particular planning context – the planning scene and the request are known,...
MotionPlanRequest request_
The planning request for this context.
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.
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.
void clear() override
Clear the data structures used by the planner.
void solve(planning_interface::MotionPlanResponse &res) override
Solve the motion planning problem and store the result in res. This function should not clear data st...
std::shared_ptr< rclcpp::Publisher< visualization_msgs::msg::MarkerArray > > getPathPublisher()
void setPathPublisher(const std::shared_ptr< rclcpp::Publisher< visualization_msgs::msg::MarkerArray > > &path_publisher)
bool terminate() override
If solve() is running, terminate the computation. Return false if termination not possible....
StompPlanningContext(const std::string &name, const std::string &group_name, const stomp_moveit::Params &params)
MoveIt-based cost functions that can be passed to STOMP via a ComposableTask.
Filter functions that can be passed to STOMP via a ComposableTask.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
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)
CostFn sum(const std::vector< CostFn > &cost_functions)
CostFn getCollisionCostFunction(const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group, double collision_penalty)
FilterFn chain(const std::vector< FilterFn > &filter_functions)
FilterFn enforcePositionBounds(const moveit::core::JointModelGroup *group)
FilterFn simpleSmoothingMatrix(size_t num_timesteps)
NoiseGeneratorFn getNormalDistributionGenerator(size_t num_timesteps, const std::vector< double > &stddev)
PostIterationFn getIterationPathPublisher(const rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr &marker_publisher, const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group)
Get post iteration function that publishes the EE path of the generated trajectory.
DoneFn getSuccessTrajectoryPublisher(const rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr &marker_publisher, const std::shared_ptr< const planning_scene::PlanningScene > &planning_scene, const moveit::core::JointModelGroup *group)
Get Done function that publishes the EE path of the generated trajectory.
Eigen::MatrixXd robotTrajectoryToMatrix(const robot_trajectory::RobotTrajectory &trajectory)
void fillRobotTrajectory(const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, robot_trajectory::RobotTrajectory &trajectory)
bool extractSeedTrajectory(const planning_interface::MotionPlanRequest &req, const moveit::core::RobotModelConstPtr &robot_model, robot_trajectory::RobotTrajectoryPtr &seed)
bool solveWithStomp(const std::shared_ptr< stomp::Stomp > &stomp, const moveit::core::RobotState &start_state, const moveit::core::RobotState &goal_state, const moveit::core::JointModelGroup *group, const robot_trajectory::RobotTrajectoryPtr &input_trajectory, robot_trajectory::RobotTrajectoryPtr &output_trajectory)
std::function< bool(const Eigen::MatrixXd &values, Eigen::VectorXd &costs, bool &validity)> CostFn
stomp::StompConfiguration getStompConfig(const stomp_moveit::Params &params, size_t num_dimensions)
std::vector< double > getPositions(const moveit::core::RobotState &state, const Joints &joints)
stomp::TaskPtr createStompTask(const stomp::StompConfiguration &config, StompPlanningContext &context)
Noise generator functions for randomizing trajectories in STOMP via a ComposableTask.
KeyboardReader input
Planning Context implementation for STOMP.
A STOMP task definition that allows injecting custom functions for planning.
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory
: Helper functions for visualizing trajectory markers for STOMP planning iterations.