planning_component.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik LLC
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 LLC 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: Henning Kayser */
36 
37 #include <stdexcept>
38 
44 #include <thread>
45 
46 namespace moveit_cpp
47 {
48 constexpr char LOGNAME[] = "planning_component";
49 
50 PlanningComponent::PlanningComponent(const std::string& group_name, const MoveItCppPtr& moveit_cpp)
51  : nh_(moveit_cpp->getNodeHandle()), moveit_cpp_(moveit_cpp), group_name_(group_name)
52 {
53  joint_model_group_ = moveit_cpp_->getRobotModel()->getJointModelGroup(group_name);
54  if (!joint_model_group_)
55  {
56  std::string error = "Could not find joint model group '" + group_name + "'.";
58  throw std::runtime_error(error);
59  }
60  plan_request_parameters_.load(nh_);
62  LOGNAME, "Plan request parameters loaded with --"
63  << " planning_pipeline: " << plan_request_parameters_.planning_pipeline << ","
64  << " planner_id: " << plan_request_parameters_.planner_id << ","
65  << " planning_time: " << plan_request_parameters_.planning_time << ","
66  << " planning_attempts: " << plan_request_parameters_.planning_attempts << ","
67  << " max_velocity_scaling_factor: " << plan_request_parameters_.max_velocity_scaling_factor << ","
68  << " max_acceleration_scaling_factor: " << plan_request_parameters_.max_acceleration_scaling_factor);
69 }
70 
71 PlanningComponent::PlanningComponent(const std::string& group_name, const ros::NodeHandle& nh)
72  : PlanningComponent(group_name, std::make_shared<MoveItCpp>(nh))
73 {
74 }
75 
76 PlanningComponent::~PlanningComponent()
77 {
78  ROS_INFO_NAMED(LOGNAME, "Deleting PlanningComponent '%s'", group_name_.c_str());
79  clearContents();
80 }
81 
82 const std::vector<std::string> PlanningComponent::getNamedTargetStates()
83 {
84  if (joint_model_group_)
85  {
86  return joint_model_group_->getDefaultStateNames();
87  }
88  else
89  {
90  ROS_WARN_NAMED(LOGNAME, "Unable to find joint group with name '%s'.", group_name_.c_str());
91  }
92 
93  std::vector<std::string> empty;
94  return empty;
95 }
96 
97 const std::string& PlanningComponent::getPlanningGroupName() const
98 {
99  return group_name_;
100 }
101 
102 bool PlanningComponent::setPathConstraints(const moveit_msgs::Constraints& path_constraints)
103 {
104  current_path_constraints_ = path_constraints;
105  return true;
106 }
107 
108 bool PlanningComponent::setTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints& trajectory_constraints)
109 {
110  current_trajectory_constraints_ = trajectory_constraints;
111  return true;
112 }
113 
114 planning_interface::MotionPlanResponse PlanningComponent::plan(const PlanRequestParameters& parameters,
115  const bool store_solution)
116 {
117  auto plan_solution = planning_interface::MotionPlanResponse();
118  if (!joint_model_group_)
119  {
120  ROS_ERROR_NAMED(LOGNAME, "Failed to retrieve joint model group for name '%s'.", group_name_.c_str());
121  plan_solution.error_code_ = moveit::core::MoveItErrorCode::INVALID_GROUP_NAME;
122  if (store_solution)
123  {
124  last_plan_solution_ = plan_solution;
125  }
126  return plan_solution;
127  }
128 
129  // Clone current planning scene
130  auto psm = moveit_cpp_->getPlanningSceneMonitorNonConst();
131  psm->updateFrameTransforms();
132  auto planning_scene = psm->copyPlanningScene();
133 
134  // Init MotionPlanRequest
136  req.group_name = group_name_;
137  req.planner_id = parameters.planner_id;
138  req.num_planning_attempts = std::max(1, parameters.planning_attempts);
139  req.allowed_planning_time = parameters.planning_time;
140  req.max_velocity_scaling_factor = parameters.max_velocity_scaling_factor;
141  req.max_acceleration_scaling_factor = parameters.max_acceleration_scaling_factor;
142  if (workspace_parameters_set_)
143  req.workspace_parameters = workspace_parameters_;
144 
145  // Set start state
146  moveit::core::RobotStatePtr start_state = considered_start_state_;
147  if (!start_state)
148  start_state = moveit_cpp_->getCurrentState();
149  start_state->update();
150  moveit::core::robotStateToRobotStateMsg(*start_state, req.start_state);
151  planning_scene->setCurrentState(*start_state);
152 
153  // Set goal constraints
154  if (current_goal_constraints_.empty())
155  {
156  ROS_ERROR_NAMED(LOGNAME, "No goal constraints set for planning request");
157  plan_solution.error_code_ = moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS;
158  if (store_solution)
159  {
160  last_plan_solution_ = plan_solution;
161  }
162  return plan_solution;
163  }
164  req.goal_constraints = current_goal_constraints_;
165 
166  // Set path constraints
167  req.path_constraints = current_path_constraints_;
168 
169  // Set trajectory constraints
170  req.trajectory_constraints = current_trajectory_constraints_;
171 
172  // Run planning attempt
174  const auto& pipelines = moveit_cpp_->getPlanningPipelines();
175  auto it = pipelines.find(parameters.planning_pipeline);
176  if (it == pipelines.end())
177  {
178  ROS_ERROR_NAMED(LOGNAME, "No planning pipeline available for name '%s'", parameters.planning_pipeline.c_str());
179  plan_solution.error_code_ = moveit::core::MoveItErrorCode::FAILURE;
180  if (store_solution)
181  {
182  last_plan_solution_ = plan_solution;
183  }
184  return plan_solution;
185  }
186  const planning_pipeline::PlanningPipelinePtr pipeline = it->second;
187  pipeline->generatePlan(planning_scene, req, res);
188  plan_solution.error_code_ = res.error_code_;
189  if (res.error_code_.val != res.error_code_.SUCCESS)
190  {
191  ROS_ERROR("Could not compute plan successfully");
192  if (store_solution)
193  {
194  last_plan_solution_ = plan_solution;
195  }
196  return plan_solution;
197  }
198  plan_solution.trajectory_ = res.trajectory_;
199  plan_solution.planning_time_ = res.planning_time_;
200  plan_solution.start_state_ = req.start_state;
201  plan_solution.error_code_ = res.error_code_.val;
202  // TODO(henningkayser): Visualize trajectory
203  // std::vector<const moveit::core::LinkModel*> eef_links;
204  // if (joint_model_group->getEndEffectorTips(eef_links))
205  //{
206  // for (const auto& eef_link : eef_links)
207  // {
208  // ROS_INFO_STREAM("Publishing trajectory for end effector " << eef_link->getName());
209  // visual_tools_->publishTrajectoryLine(last_solution_trajectory_, eef_link);
210  // visual_tools_->publishTrajectoryPath(last_solution_trajectory_, false);
211  // visual_tools_->publishRobotState(last_solution_trajectory_->getLastWayPoint(), rviz_visual_tools::TRANSLUCENT);
212  // }
213  //}
214 
215  if (store_solution)
216  {
217  last_plan_solution_ = plan_solution;
218  }
219  return plan_solution;
220 }
221 
223 PlanningComponent::plan(const MultiPipelinePlanRequestParameters& parameters,
224  const SolutionCallbackFunction& solution_selection_callback,
225  const StoppingCriterionFunction& stopping_criterion_callback)
226 {
227  // Create solutions container
228  PlanningComponent::PlanSolutions planning_solutions{ parameters.multi_plan_request_parameters.size() };
229  std::vector<std::thread> planning_threads;
230  planning_threads.reserve(parameters.multi_plan_request_parameters.size());
231 
232  // Print a warning if more parallel planning problems than available concurrent threads are defined. If
233  // std::thread::hardware_concurrency() is not defined, the command returns 0 so the check does not work
234  auto const hardware_concurrency = std::thread::hardware_concurrency();
235  if (parameters.multi_plan_request_parameters.size() > hardware_concurrency && hardware_concurrency != 0)
236  {
238  LOGNAME,
239  "More parallel planning problems defined ('%ld') than possible to solve concurrently with the hardware ('%d')",
240  parameters.multi_plan_request_parameters.size(), hardware_concurrency);
241  }
242 
243  // Launch planning threads
244  for (auto const& plan_request_parameter : parameters.multi_plan_request_parameters)
245  {
246  auto planning_thread = std::thread([&]() {
247  auto plan_solution = planning_interface::MotionPlanResponse();
248  try
249  {
250  plan_solution = plan(plan_request_parameter, false);
251  }
252  catch (const std::exception& e)
253  {
254  ROS_ERROR_STREAM_NAMED(LOGNAME, "Planning pipeline '" << plan_request_parameter.planning_pipeline.c_str()
255  << "' threw exception '" << e.what() << "'");
256  plan_solution.error_code_ = moveit::core::MoveItErrorCode::FAILURE;
257  }
258  plan_solution.planner_id_ = plan_request_parameter.planner_id;
259  planning_solutions.pushBack(plan_solution);
260 
261  if (stopping_criterion_callback != nullptr)
262  {
263  if (stopping_criterion_callback(planning_solutions, parameters))
264  {
265  // Terminate planning pipelines
267  "Stopping criterion met: Terminating planning pipelines that are still active");
268  for (auto const& plan_request_parameter : parameters.multi_plan_request_parameters)
269  {
270  moveit_cpp_->terminatePlanningPipeline(plan_request_parameter.planning_pipeline);
271  }
272  }
273  }
274  });
275  planning_threads.push_back(std::move(planning_thread));
276  }
277 
278  // Wait for threads to finish
279  for (auto& planning_thread : planning_threads)
280  {
281  if (planning_thread.joinable())
282  {
283  planning_thread.join();
284  }
285  }
286 
287  // Return best solution determined by user defined callback (Default: Shortest path)
288  last_plan_solution_ = solution_selection_callback(planning_solutions.getSolutions());
289  return last_plan_solution_;
290 }
291 
292 planning_interface::MotionPlanResponse PlanningComponent::plan()
293 {
294  return plan(plan_request_parameters_);
295 }
296 
297 bool PlanningComponent::setStartState(const moveit::core::RobotState& start_state)
298 {
299  considered_start_state_ = std::make_shared<moveit::core::RobotState>(start_state);
300  return true;
301 }
302 
303 moveit::core::RobotStatePtr PlanningComponent::getStartState()
304 {
305  if (considered_start_state_)
306  return considered_start_state_;
307  else
308  {
309  moveit::core::RobotStatePtr s;
310  moveit_cpp_->getCurrentState(s, 1.0);
311  return s;
312  }
313 }
314 
315 bool PlanningComponent::setStartState(const std::string& start_state_name)
316 {
317  const auto& named_targets = getNamedTargetStates();
318  if (std::find(named_targets.begin(), named_targets.end(), start_state_name) == named_targets.end())
319  {
320  ROS_ERROR_NAMED(LOGNAME, "No predefined joint state found for target name '%s'", start_state_name.c_str());
321  return false;
322  }
323  moveit::core::RobotState start_state(moveit_cpp_->getRobotModel());
324  start_state.setToDefaultValues(joint_model_group_, start_state_name);
325  return setStartState(start_state);
326 }
327 
328 void PlanningComponent::setStartStateToCurrentState()
329 {
330  considered_start_state_.reset();
331 }
332 
333 std::map<std::string, double> PlanningComponent::getNamedTargetStateValues(const std::string& name)
334 {
335  // TODO(henningkayser): verify result
336  std::map<std::string, double> positions;
337  joint_model_group_->getVariableDefaultPositions(name, positions);
338  return positions;
339 }
340 
341 void PlanningComponent::setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
342 {
343  workspace_parameters_.header.frame_id = moveit_cpp_->getRobotModel()->getModelFrame();
344  workspace_parameters_.header.stamp = ros::Time::now();
345  workspace_parameters_.min_corner.x = minx;
346  workspace_parameters_.min_corner.y = miny;
347  workspace_parameters_.min_corner.z = minz;
348  workspace_parameters_.max_corner.x = maxx;
349  workspace_parameters_.max_corner.y = maxy;
350  workspace_parameters_.max_corner.z = maxz;
351  workspace_parameters_set_ = true;
352 }
353 
354 void PlanningComponent::unsetWorkspace()
355 {
356  workspace_parameters_set_ = false;
357 }
358 
359 bool PlanningComponent::setGoal(const std::vector<moveit_msgs::Constraints>& goal_constraints)
360 {
361  current_goal_constraints_ = goal_constraints;
362  return true;
363 }
364 
365 bool PlanningComponent::setGoal(const moveit::core::RobotState& goal_state)
366 {
367  current_goal_constraints_ = { kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group_) };
368  return true;
369 }
370 
371 bool PlanningComponent::setGoal(const geometry_msgs::PoseStamped& goal_pose, const std::string& link_name)
372 {
373  current_goal_constraints_ = { kinematic_constraints::constructGoalConstraints(link_name, goal_pose) };
374  return true;
375 }
376 
377 bool PlanningComponent::setGoal(const std::string& goal_state_name)
378 {
379  const auto& named_targets = getNamedTargetStates();
380  if (std::find(named_targets.begin(), named_targets.end(), goal_state_name) == named_targets.end())
381  {
382  ROS_ERROR_NAMED(LOGNAME, "No predefined joint state found for target name '%s'", goal_state_name.c_str());
383  return false;
384  }
385  moveit::core::RobotState goal_state(moveit_cpp_->getRobotModel());
386  goal_state.setToDefaultValues(joint_model_group_, goal_state_name);
387  return setGoal(goal_state);
388 }
389 
390 bool PlanningComponent::execute(bool blocking)
391 {
392  if (!last_plan_solution_)
393  {
394  ROS_ERROR_NAMED(LOGNAME, "There is no successful plan to execute");
395  return false;
396  }
397 
398  // TODO(henningkayser): parameterize timestamps if required
399  // trajectory_processing::TimeOptimalTrajectoryGeneration totg;
400  // if (!totg.computeTimeStamps(*last_solution_trajectory_, max_velocity_scaling_factor_,
401  // max_acceleration_scaling_factor_))
402  //{
403  // ROS_ERROR("Failed to parameterize trajectory");
404  // return false;
405  //}
406  return moveit_cpp_->execute(group_name_, last_plan_solution_.trajectory_, blocking);
407 }
408 
409 planning_interface::MotionPlanResponse const& PlanningComponent::getLastMotionPlanResponse()
410 {
411  return last_plan_solution_;
412 }
413 
415 getShortestSolution(std::vector<planning_interface::MotionPlanResponse> const& solutions)
416 {
417  // Find trajectory with minimal path
418  auto const shortest_trajectory = std::min_element(solutions.begin(), solutions.end(),
419  [](planning_interface::MotionPlanResponse const& solution_a,
420  planning_interface::MotionPlanResponse const& solution_b) {
421  // If both solutions were successful, check which path is shorter
422  if (solution_a && solution_b)
423  {
424  return robot_trajectory::path_length(*solution_a.trajectory_) <
425  robot_trajectory::path_length(*solution_b.trajectory_);
426  }
427  // If only solution a is successful, return a
428  else if (solution_a)
429  {
430  return true;
431  }
432  // Else return solution b, either because it is successful or not
433  return false;
434  });
435  if (shortest_trajectory->trajectory_ != nullptr)
436  {
437  ROS_INFO_NAMED(LOGNAME, "Chosen solution with shortest path length: '%f'",
438  robot_trajectory::path_length(*shortest_trajectory->trajectory_));
439  }
440  else
441  {
442  ROS_INFO_STREAM_NAMED(LOGNAME, "Could not determine shortest path");
443  }
444  return *shortest_trajectory;
445 }
446 
447 void PlanningComponent::clearContents()
448 {
449  considered_start_state_.reset();
450  last_plan_solution_ = planning_interface::MotionPlanResponse();
451  current_goal_constraints_.clear();
452  moveit_cpp_.reset();
453 }
454 } // namespace moveit_cpp
moveit_cpp::PlanningComponent::PlanRequestParameters::planning_attempts
int planning_attempts
Definition: planning_component.h:127
planning_interface::MotionPlanResponse
utils.h
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
s
XmlRpcServer s
moveit_cpp::PlanningComponent::PlanRequestParameters::max_acceleration_scaling_factor
double max_acceleration_scaling_factor
Definition: planning_component.h:130
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
kinematic_constraints::constructGoalConstraints
moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
robot_trajectory::path_length
double path_length(RobotTrajectory const &trajectory)
moveit_cpp::PlanningComponent::PlanRequestParameters::planning_pipeline
std::string planning_pipeline
Definition: planning_component.h:126
moveit_cpp
Definition: moveit_cpp.h:50
moveit_cpp::PlanningComponent::PlanRequestParameters::planner_id
std::string planner_id
Definition: planning_component.h:125
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
ROS_ERROR
#define ROS_ERROR(...)
moveit_cpp::PlanningComponent::PlanRequestParameters
Planner parameters provided with the MotionPlanRequest.
Definition: planning_component.h:123
moveit_cpp::PlanningComponent::PlanRequestParameters::planning_time
double planning_time
Definition: planning_component.h:128
planning_scene_monitor.h
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
planning_component.h
moveit_cpp::PlanningComponent::PlanRequestParameters::max_velocity_scaling_factor
double max_velocity_scaling_factor
Definition: planning_component.h:129
LOGNAME
static const std::string LOGNAME
Definition: collision_plugin_loader.cpp:37
moveit_cpp::getShortestSolution
planning_interface::MotionPlanResponse getShortestSolution(std::vector< planning_interface::MotionPlanResponse > const &solutions)
A function to choose the solution with the shortest path from a vector of solutions.
Definition: planning_component.cpp:447
std
planning_pipeline.h
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
conversions.h
moveit_cpp::PlanningComponent::PlanningComponent
PlanningComponent(const std::string &group_name, const ros::NodeHandle &nh)
Constructor.
Definition: planning_component.cpp:103
planning_interface::MotionPlanResponse::planning_time_
double planning_time_
planning_scene
moveit_cpp::LOGNAME
constexpr char LOGNAME[]
Definition: moveit_cpp.cpp:74
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
ros::NodeHandle
moveit::planning_interface::PlanningComponent
moveit_cpp::PlanningComponent PlanningComponent
Definition: planning_component.h:265
moveit::planning_interface::MoveItCpp
moveit_cpp::MoveItCpp MoveItCpp
Definition: moveit_cpp.h:192
ros::Time::now
static Time now()


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:27:54