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