moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
chomp_planner.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: E. Gil Jones */
36
41// TODO: Remove conditional include when released to all active distros.
42#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
43#include <tf2/LinearMath/Quaternion.hpp>
44#else
45#include <tf2/LinearMath/Quaternion.h>
46#endif
47#include <tf2_eigen/tf2_eigen.hpp>
48#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
50
51#include <chrono>
52
53namespace chomp
54{
55namespace
56{
57rclcpp::Logger getLogger()
58{
59 return moveit::getLogger("moveit.planners.chomp.planner");
60}
61} // namespace
62
63void ChompPlanner::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
66{
67 auto start_time = std::chrono::system_clock::now();
68 res.planner_id = std::string("chomp");
69 if (!planning_scene)
70 {
71 RCLCPP_ERROR(getLogger(), "No planning scene initialized.");
72 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
73 return;
74 }
75
76 // get the specified start state
77 moveit::core::RobotState start_state = planning_scene->getCurrentState();
78 moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
79
80 if (!start_state.satisfiesBounds())
81 {
82 RCLCPP_ERROR(getLogger(), "Start state violates joint limits");
83 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
84 return;
85 }
86
87 ChompTrajectory trajectory(planning_scene->getRobotModel(), 3.0, .03, req.group_name);
88 robotStateToArray(start_state, req.group_name, trajectory.getTrajectoryPoint(0));
89
90 if (req.goal_constraints.size() != 1)
91 {
92 RCLCPP_ERROR(getLogger(), "Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
93 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
94 return;
95 }
96
97 if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
98 !req.goal_constraints[0].orientation_constraints.empty())
99 {
100 RCLCPP_ERROR(getLogger(), "Only joint-space goals are supported");
101 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
102 return;
103 }
104
105 const size_t goal_index = trajectory.getNumPoints() - 1;
106 moveit::core::RobotState goal_state(start_state);
107 for (const moveit_msgs::msg::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
108 goal_state.setVariablePosition(joint_constraint.joint_name, joint_constraint.position);
109 if (!goal_state.satisfiesBounds())
110 {
111 RCLCPP_ERROR(getLogger(), "Goal state violates joint limits");
112 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
113 return;
114 }
115 robotStateToArray(goal_state, req.group_name, trajectory.getTrajectoryPoint(goal_index));
116
117 const moveit::core::JointModelGroup* model_group =
118 planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
119 // fix the goal to move the shortest angular distance for wrap-around joints:
120 for (size_t i = 0; i < model_group->getActiveJointModels().size(); ++i)
121 {
122 const moveit::core::JointModel* model = model_group->getActiveJointModels()[i];
123 const moveit::core::RevoluteJointModel* revolute_joint =
124 dynamic_cast<const moveit::core::RevoluteJointModel*>(model);
125
126 if (revolute_joint != nullptr)
127 {
128 if (revolute_joint->isContinuous())
129 {
130 double start = (trajectory)(0, i);
131 double end = (trajectory)(goal_index, i);
132 RCLCPP_INFO(getLogger(), "Start is %f end %f short %f", start, end, shortestAngularDistance(start, end));
133 (trajectory)(goal_index, i) = start + shortestAngularDistance(start, end);
134 }
135 }
136 }
137
138 // fill in an initial trajectory based on user choice from the chomp_config.yaml file
139 if (params.trajectory_initialization_method_.compare("quintic-spline") == 0)
140 {
141 trajectory.fillInMinJerk();
142 }
143 else if (params.trajectory_initialization_method_.compare("linear") == 0)
144 {
145 trajectory.fillInLinearInterpolation();
146 }
147 else if (params.trajectory_initialization_method_.compare("cubic") == 0)
148 {
149 trajectory.fillInCubicInterpolation();
150 }
151 else if (params.trajectory_initialization_method_.compare("fillTrajectory") == 0)
152 {
153 if (res.trajectory.empty())
154 {
155 RCLCPP_ERROR(getLogger(), "No input trajectory specified");
156 return;
157 }
158 else if (!(trajectory.fillInFromTrajectory(*res.trajectory[0])))
159 {
160 RCLCPP_ERROR(getLogger(), "Input trajectory has less than 2 points, "
161 "trajectory must contain at least start and goal state");
162 return;
163 }
164 }
165 else
166 {
167 RCLCPP_ERROR(getLogger(), "invalid interpolation method specified in the chomp_planner file");
168 return;
169 }
170
171 RCLCPP_INFO(getLogger(), "CHOMP trajectory initialized using method: %s ",
172 (params.trajectory_initialization_method_).c_str());
173
174 // optimize!
175 auto create_time = std::chrono::system_clock::now();
176
177 int replan_count = 0;
178 bool replan_flag = false;
179 double org_learning_rate = 0.04, org_ridge_factor = 0.0, org_planning_time_limit = 10;
180 int org_max_iterations = 200;
181
182 // storing the initial chomp parameters values
183 org_learning_rate = params.learning_rate_;
184 org_ridge_factor = params.ridge_factor_;
185 org_planning_time_limit = params.planning_time_limit_;
186 org_max_iterations = params.max_iterations_;
187
188 std::unique_ptr<ChompOptimizer> optimizer;
189
190 // create a non_const_params variable which stores the non constant version of the const params variable
191 ChompParameters params_nonconst = params;
192
193 // while loop for replanning (recovery behaviour) if collision free optimized solution not found
194 while (true)
195 {
196 if (replan_flag)
197 {
198 // increase learning rate in hope to find a successful path; increase ridge factor to avoid obstacles; add 5
199 // additional secs in hope to find a solution; increase maximum iterations
200 params_nonconst.setRecoveryParams(params_nonconst.learning_rate_ + 0.02, params_nonconst.ridge_factor_ + 0.002,
201 params_nonconst.planning_time_limit_ + 5, params_nonconst.max_iterations_ + 50);
202 }
203
204 // initialize a ChompOptimizer object to load up the optimizer with default parameters or with updated parameters in
205 // case of a recovery behaviour
206 optimizer =
207 std::make_unique<ChompOptimizer>(&trajectory, planning_scene, req.group_name, &params_nonconst, start_state);
208 if (!optimizer->isInitialized())
209 {
210 RCLCPP_ERROR(getLogger(), "Could not initialize optimizer");
211 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
212 return;
213 }
214
215 RCLCPP_DEBUG(getLogger(), "Optimization took %ld sec to create",
216 (std::chrono::system_clock::now() - create_time).count());
217
218 bool optimization_result = optimizer->optimize();
219
220 // replan with updated parameters if no solution is found
221 if (params_nonconst.enable_failure_recovery_)
222 {
223 RCLCPP_INFO(getLogger(),
224 "Planned with Chomp Parameters (learning_rate, ridge_factor, "
225 "planning_time_limit, max_iterations), attempt: # %d ",
226 (replan_count + 1));
227 RCLCPP_INFO(getLogger(), "Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
228 params_nonconst.learning_rate_, params_nonconst.ridge_factor_, params_nonconst.planning_time_limit_,
229 params_nonconst.max_iterations_);
230
231 if (!optimization_result && replan_count < params_nonconst.max_recovery_attempts_)
232 {
233 replan_count++;
234 replan_flag = true;
235 }
236 else
237 {
238 break;
239 }
240 }
241 else
242 break;
243 } // end of while loop
244
245 // resetting the CHOMP Parameters to the original values after a successful plan
246 params_nonconst.setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
247
248 RCLCPP_DEBUG(getLogger(), "Optimization actually took %ld sec to run",
249 (std::chrono::system_clock::now() - create_time).count());
250 create_time = std::chrono::system_clock::now();
251 // assume that the trajectory is now optimized, fill in the output structure:
252
253 RCLCPP_DEBUG(getLogger(), "Output trajectory has %zd joints", trajectory.getNumJoints());
254
255 auto result = std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene->getRobotModel(), req.group_name);
256 // fill in the entire trajectory
257 for (size_t i = 0; i < trajectory.getNumPoints(); ++i)
258 {
259 const Eigen::MatrixXd::RowXpr source = trajectory.getTrajectoryPoint(i);
260 auto state = std::make_shared<moveit::core::RobotState>(start_state);
261 size_t joint_index = 0;
262 for (const moveit::core::JointModel* jm : result->getGroup()->getActiveJointModels())
263 {
264 assert(jm->getVariableCount() == 1);
265 state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
266 }
267 result->addSuffixWayPoint(state, 0.0);
268 }
269
270 res.trajectory.resize(1);
271 res.trajectory[0] = result;
272 res.description.resize(1);
273 res.description[0] = "plan";
274
275 RCLCPP_DEBUG(getLogger(), "Bottom took %ld sec to create", (std::chrono::system_clock::now() - create_time).count());
276 RCLCPP_DEBUG(getLogger(), "Serviced planning request in %ld wall-seconds",
277 (std::chrono::system_clock::now() - start_time).count());
278
279 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
280 res.processing_time.resize(1);
281 res.processing_time[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
282
283 // report planning failure if path has collisions
284 if (!optimizer->isCollisionFree())
285 {
286 RCLCPP_ERROR(getLogger(), "Motion plan is invalid.");
287 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
288 return;
289 }
290
291 // check that final state is within goal tolerances
293 const moveit::core::RobotState& last_state = result->getLastWayPoint();
294 for (const moveit_msgs::msg::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
295 {
296 if (!jc.configure(constraint) || !jc.decide(last_state).satisfied)
297 {
298 RCLCPP_ERROR(getLogger(), "Goal constraints are violated: %s", constraint.joint_name.c_str());
299 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;
300 return;
301 }
302 }
303
304 res.processing_time.resize(1);
305 res.processing_time[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
306}
307
308} // namespace chomp
std::string trajectory_initialization_method_
void setRecoveryParams(double learning_rate, double ridge_factor, int planning_time_limit, int max_iterations)
void solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, const ChompParameters &params, planning_interface::MotionPlanDetailedResponse &res) const
Represents a discretized joint-space trajectory for CHOMP.
size_t getNumPoints() const
Gets the number of points in the trajectory.
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
bool fillInFromTrajectory(const robot_trajectory::RobotTrajectory &trajectory)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e....
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Class for handling single DOF joint constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
bool isContinuous() const
Check if this joint wraps around.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
bool satisfiesBounds(double margin=0.0) const
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
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
bool satisfied
Whether or not the constraint or constraints were satisfied.
moveit_msgs::msg::MoveItErrorCodes error_code
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory