moveit2
The MoveIt Motion Planning Framework for ROS 2.
command_list_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 
36 
37 #include <rclcpp/logger.hpp>
38 #include <rclcpp/logging.hpp>
39 #include <cassert>
40 #include <functional>
41 #include <sstream>
42 
50 
52 {
53 static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
54 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner.command_list_manager");
55 
56 CommandListManager::CommandListManager(const rclcpp::Node::SharedPtr& node,
57  const moveit::core::RobotModelConstPtr& model)
58  : node_(node), model_(model)
59 {
60  // Obtain the aggregated joint limits
61  pilz_industrial_motion_planner::JointLimitsContainer aggregated_limit_active_joints;
62 
64  node_, PARAM_NAMESPACE_LIMITS, model_->getActiveJointModels());
65 
66  // Obtain cartesian limits
69 
71  limits.setJointLimits(aggregated_limit_active_joints);
72  limits.setCartesianLimits(cartesian_limit);
73 
74  plan_comp_builder_.setModel(model);
75  plan_comp_builder_.setBlender(std::unique_ptr<pilz_industrial_motion_planner::TrajectoryBlender>(
77 }
78 
79 RobotTrajCont CommandListManager::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
80  const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
81  const moveit_msgs::msg::MotionSequenceRequest& req_list)
82 {
83  if (req_list.items.empty())
84  {
85  return RobotTrajCont();
86  }
87 
88  checkForNegativeRadii(req_list);
89  checkLastBlendRadiusZero(req_list);
90  checkStartStates(req_list);
91 
92  MotionResponseCont resp_cont{ solveSequenceItems(planning_scene, planning_pipeline, req_list) };
93 
94  assert(model_);
95  RadiiCont radii{ extractBlendRadii(*model_, req_list) };
96  checkForOverlappingRadii(resp_cont, radii);
97 
98  plan_comp_builder_.reset();
99  for (MotionResponseCont::size_type i = 0; i < resp_cont.size(); ++i)
100  {
101  plan_comp_builder_.append(planning_scene, resp_cont.at(i).trajectory_,
102  // The blend radii has to be "attached" to
103  // the second part of a blend trajectory,
104  // therefore: "i-1".
105  (i > 0 ? radii.at(i - 1) : 0.));
106  }
107  return plan_comp_builder_.build();
108 }
109 
110 bool CommandListManager::checkRadiiForOverlap(const robot_trajectory::RobotTrajectory& traj_A, const double radii_A,
111  const robot_trajectory::RobotTrajectory& traj_B,
112  const double radii_B) const
113 {
114  // No blending between trajectories from different groups
115  if (traj_A.getGroupName() != traj_B.getGroupName())
116  {
117  return false;
118  }
119 
120  auto sum_radii{ radii_A + radii_B };
121  if (sum_radii == 0.)
122  {
123  return false;
124  }
125 
126  const std::string& blend_frame{ getSolverTipFrame(model_->getJointModelGroup(traj_A.getGroupName())) };
127  auto distance_endpoints = (traj_A.getLastWayPoint().getFrameTransform(blend_frame).translation() -
128  traj_B.getLastWayPoint().getFrameTransform(blend_frame).translation())
129  .norm();
130  return distance_endpoints <= sum_radii;
131 }
132 
133 void CommandListManager::checkForOverlappingRadii(const MotionResponseCont& resp_cont, const RadiiCont& radii) const
134 {
135  if (resp_cont.empty())
136  {
137  return;
138  }
139  if (resp_cont.size() < 3)
140  {
141  return;
142  }
143 
144  for (MotionResponseCont::size_type i = 0; i < resp_cont.size() - 2; ++i)
145  {
146  if (checkRadiiForOverlap(*(resp_cont.at(i).trajectory_), radii.at(i), *(resp_cont.at(i + 1).trajectory_),
147  radii.at(i + 1)))
148  {
149  std::ostringstream os;
150  os << "Overlapping blend radii between command [" << i << "] and [" << i + 1 << "].";
151  throw OverlappingBlendRadiiException(os.str());
152  }
153  }
154 }
155 
156 CommandListManager::RobotState_OptRef
157 CommandListManager::getPreviousEndState(const MotionResponseCont& motion_plan_responses, const std::string& group_name)
158 {
159  for (MotionResponseCont::const_reverse_iterator it = motion_plan_responses.crbegin();
160  it != motion_plan_responses.crend(); ++it)
161  {
162  if (it->trajectory_->getGroupName() == group_name)
163  {
164  return std::reference_wrapper(it->trajectory_->getLastWayPoint());
165  }
166  }
167  return {};
168 }
169 
170 void CommandListManager::setStartState(const MotionResponseCont& motion_plan_responses, const std::string& group_name,
171  moveit_msgs::msg::RobotState& start_state)
172 {
173  RobotState_OptRef rob_state_op{ getPreviousEndState(motion_plan_responses, group_name) };
174  if (rob_state_op)
175  {
176  moveit::core::robotStateToRobotStateMsg(rob_state_op.value(), start_state, false);
177  start_state.is_diff = true;
178  }
179 }
180 
181 bool CommandListManager::isInvalidBlendRadii(const moveit::core::RobotModel& model,
182  const moveit_msgs::msg::MotionSequenceItem& item_A,
183  const moveit_msgs::msg::MotionSequenceItem& item_B)
184 {
185  // Zero blend radius is always valid
186  if (item_A.blend_radius == 0.)
187  {
188  return false;
189  }
190 
191  // No blending between different groups
192  if (item_A.req.group_name != item_B.req.group_name)
193  {
194  RCLCPP_WARN_STREAM(LOGGER, "Blending between different groups (in this case: \""
195  << item_A.req.group_name << "\" and \"" << item_B.req.group_name
196  << "\") not allowed");
197  return true;
198  }
199 
200  // No blending for groups without solver
201  if (!hasSolver(model.getJointModelGroup(item_A.req.group_name)))
202  {
203  RCLCPP_WARN_STREAM(LOGGER, "Blending for groups without solver not allowed");
204  return true;
205  }
206 
207  return false;
208 }
209 
210 CommandListManager::RadiiCont
211 CommandListManager::extractBlendRadii(const moveit::core::RobotModel& model,
212  const moveit_msgs::msg::MotionSequenceRequest& req_list)
213 {
214  RadiiCont radii(req_list.items.size(), 0.);
215  for (RadiiCont::size_type i = 0; i < (radii.size() - 1); ++i)
216  {
217  if (isInvalidBlendRadii(model, req_list.items.at(i), req_list.items.at(i + 1)))
218  {
219  RCLCPP_WARN_STREAM(LOGGER, "Invalid blend radii between commands: [" << i << "] and [" << i + 1
220  << "] => Blend radii set to zero");
221  continue;
222  }
223  radii.at(i) = req_list.items.at(i).blend_radius;
224  }
225  return radii;
226 }
227 
228 CommandListManager::MotionResponseCont
229 CommandListManager::solveSequenceItems(const planning_scene::PlanningSceneConstPtr& planning_scene,
230  const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
231  const moveit_msgs::msg::MotionSequenceRequest& req_list) const
232 {
233  MotionResponseCont motion_plan_responses;
234  size_t curr_req_index{ 0 };
235  const size_t num_req{ req_list.items.size() };
236  for (const auto& seq_item : req_list.items)
237  {
238  planning_interface::MotionPlanRequest req{ seq_item.req };
239  setStartState(motion_plan_responses, req.group_name, req.start_state);
240 
242  planning_pipeline->generatePlan(planning_scene, req, res);
243  if (res.error_code_.val != res.error_code_.SUCCESS)
244  {
245  std::ostringstream os;
246  os << "Could not solve request\n"; // TODO(henning): re-enable "---\n" << req << "\n---\n";
247  throw PlanningPipelineException(os.str(), res.error_code_.val);
248  }
249  motion_plan_responses.emplace_back(res);
250  RCLCPP_DEBUG_STREAM(LOGGER, "Solved [" << ++curr_req_index << "/" << num_req << "]");
251  }
252  return motion_plan_responses;
253 }
254 
255 void CommandListManager::checkForNegativeRadii(const moveit_msgs::msg::MotionSequenceRequest& req_list)
256 {
257  if (!std::all_of(req_list.items.begin(), req_list.items.end(),
258  [](const moveit_msgs::msg::MotionSequenceItem& req) { return (req.blend_radius >= 0.); }))
259  {
260  throw NegativeBlendRadiusException("All blending radii MUST be non negative");
261  }
262 }
263 
264 void CommandListManager::checkStartStatesOfGroup(const moveit_msgs::msg::MotionSequenceRequest& req_list,
265  const std::string& group_name)
266 {
267  bool first_elem{ true };
268  for (const moveit_msgs::msg::MotionSequenceItem& item : req_list.items)
269  {
270  if (item.req.group_name != group_name)
271  {
272  continue;
273  }
274 
275  if (first_elem)
276  {
277  first_elem = false;
278  continue;
279  }
280 
281  if (!(item.req.start_state.joint_state.position.empty() && item.req.start_state.joint_state.velocity.empty() &&
282  item.req.start_state.joint_state.effort.empty() && item.req.start_state.joint_state.name.empty()))
283  {
284  std::ostringstream os;
285  os << "Only the first request is allowed to have a start state, but"
286  << " the requests for group: \"" << group_name << "\" violate the rule";
287  throw StartStateSetException(os.str());
288  }
289  }
290 }
291 
292 void CommandListManager::checkStartStates(const moveit_msgs::msg::MotionSequenceRequest& req_list)
293 {
294  if (req_list.items.size() <= 1)
295  {
296  return;
297  }
298 
299  GroupNamesCont group_names{ getGroupNames(req_list) };
300  for (const auto& curr_group_name : group_names)
301  {
302  checkStartStatesOfGroup(req_list, curr_group_name);
303  }
304 }
305 
306 CommandListManager::GroupNamesCont
307 CommandListManager::getGroupNames(const moveit_msgs::msg::MotionSequenceRequest& req_list)
308 {
309  GroupNamesCont group_names;
310  std::for_each(req_list.items.cbegin(), req_list.items.cend(),
311  [&group_names](const moveit_msgs::msg::MotionSequenceItem& item) {
312  if (std::find(group_names.cbegin(), group_names.cend(), item.req.group_name) == group_names.cend())
313  {
314  group_names.emplace_back(item.req.group_name);
315  }
316  });
317  return group_names;
318 }
319 
320 } // namespace pilz_industrial_motion_planner
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
static CartesianLimit getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace)
Loads cartesian limits from the node parameters.
CommandListManager(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &model)
RobotTrajCont solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_pipeline::PlanningPipelinePtr &planning_pipeline, const moveit_msgs::msg::MotionSequenceRequest &req_list)
Generates trajectories for the specified list of motion commands.
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
void setCartesianLimits(CartesianLimit &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
std::vector< robot_trajectory::RobotTrajectoryPtr > build() const
void reset()
Clears the trajectory container under construction.
void setModel(const moveit::core::RobotModelConstPtr &model)
Sets the robot model needed to create new trajectory elements.
void setBlender(std::unique_ptr< pilz_industrial_motion_planner::TrajectoryBlender > blender)
Sets the blender used to blend two trajectories.
void append(const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_trajectory::RobotTrajectoryPtr &other, const double blend_radius)
Appends the specified trajectory to the trajectory container under construction.
Trajectory blender implementing transition window algorithm.
Maintain a sequence of waypoints and the time durations between these waypoints.
const std::string & getGroupName() const
const moveit::core::RobotState & getLastWayPoint() const
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Planning pipeline.
This namespace includes the central class for representing planning contexts.
moveit_msgs::msg::MoveItErrorCodes error_code_