37 #include <rclcpp/logger.hpp> 
   38 #include <rclcpp/logging.hpp> 
   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");
 
   57                                        const moveit::core::RobotModelConstPtr& model)
 
   58   : node_(node), model_(model)
 
   64       node_, PARAM_NAMESPACE_LIMITS, model_->getActiveJointModels());
 
   75   plan_comp_builder_.
setBlender(std::unique_ptr<pilz_industrial_motion_planner::TrajectoryBlender>(
 
   81                                         const moveit_msgs::msg::MotionSequenceRequest& req_list)
 
   83   if (req_list.items.empty())
 
   88   checkForNegativeRadii(req_list);
 
   89   checkLastBlendRadiusZero(req_list);
 
   90   checkStartStates(req_list);
 
   95   RadiiCont radii{ extractBlendRadii(*model_, req_list) };
 
   96   checkForOverlappingRadii(resp_cont, radii);
 
   98   plan_comp_builder_.
reset();
 
   99   for (MotionResponseCont::size_type i = 0; i < resp_cont.size(); ++i)
 
  105                               (i > 0 ? radii.at(i - 1) : 0.));
 
  107   return plan_comp_builder_.
build();
 
  112                                               const double radii_B)
 const 
  120   auto sum_radii{ radii_A + radii_B };
 
  126   const std::string& blend_frame{ getSolverTipFrame(model_->getJointModelGroup(traj_A.
getGroupName())) };
 
  130   return distance_endpoints <= sum_radii;
 
  133 void CommandListManager::checkForOverlappingRadii(
const MotionResponseCont& resp_cont, 
const RadiiCont& radii)
 const 
  135   if (resp_cont.empty())
 
  139   if (resp_cont.size() < 3)
 
  144   for (MotionResponseCont::size_type i = 0; i < resp_cont.size() - 2; ++i)
 
  146     if (checkRadiiForOverlap(*(resp_cont.at(i).trajectory_), radii.at(i), *(resp_cont.at(i + 1).trajectory_),
 
  149       std::ostringstream os;
 
  150       os << 
"Overlapping blend radii between command [" << i << 
"] and [" << i + 1 << 
"].";
 
  151       throw OverlappingBlendRadiiException(os.str());
 
  156 CommandListManager::RobotState_OptRef
 
  157 CommandListManager::getPreviousEndState(
const MotionResponseCont& motion_plan_responses, 
const std::string& group_name)
 
  159   for (MotionResponseCont::const_reverse_iterator it = motion_plan_responses.crbegin();
 
  160        it != motion_plan_responses.crend(); ++it)
 
  162     if (it->trajectory_->getGroupName() == group_name)
 
  164       return std::reference_wrapper(it->trajectory_->getLastWayPoint());
 
  170 void CommandListManager::setStartState(
const MotionResponseCont& motion_plan_responses, 
const std::string& group_name,
 
  171                                        moveit_msgs::msg::RobotState& start_state)
 
  173   RobotState_OptRef rob_state_op{ getPreviousEndState(motion_plan_responses, group_name) };
 
  177     start_state.is_diff = 
true;
 
  182                                              const moveit_msgs::msg::MotionSequenceItem& item_A,
 
  183                                              const moveit_msgs::msg::MotionSequenceItem& item_B)
 
  186   if (item_A.blend_radius == 0.)
 
  192   if (item_A.req.group_name != item_B.req.group_name)
 
  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");
 
  203     RCLCPP_WARN_STREAM(LOGGER, 
"Blending for groups without solver not allowed");
 
  210 CommandListManager::RadiiCont
 
  212                                       const moveit_msgs::msg::MotionSequenceRequest& req_list)
 
  214   RadiiCont radii(req_list.items.size(), 0.);
 
  215   for (RadiiCont::size_type i = 0; i < (radii.size() - 1); ++i)
 
  217     if (isInvalidBlendRadii(model, req_list.items.at(i), req_list.items.at(i + 1)))
 
  219       RCLCPP_WARN_STREAM(LOGGER, 
"Invalid blend radii between commands: [" << i << 
"] and [" << i + 1
 
  220                                                                            << 
"] => Blend radii set to zero");
 
  223     radii.at(i) = req_list.items.at(i).blend_radius;
 
  228 CommandListManager::MotionResponseCont
 
  229 CommandListManager::solveSequenceItems(
const planning_scene::PlanningSceneConstPtr& 
planning_scene,
 
  231                                        const moveit_msgs::msg::MotionSequenceRequest& req_list)
 const 
  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)
 
  239     setStartState(motion_plan_responses, req.group_name, req.start_state);
 
  245       std::ostringstream os;
 
  246       os << 
"Could not solve request\n";  
 
  247       throw PlanningPipelineException(os.str(), res.
error_code_.val);
 
  249     motion_plan_responses.emplace_back(res);
 
  250     RCLCPP_DEBUG_STREAM(LOGGER, 
"Solved [" << ++curr_req_index << 
"/" << num_req << 
"]");
 
  252   return motion_plan_responses;
 
  255 void CommandListManager::checkForNegativeRadii(
const moveit_msgs::msg::MotionSequenceRequest& req_list)
 
  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.); }))
 
  260     throw NegativeBlendRadiusException(
"All blending radii MUST be non negative");
 
  264 void CommandListManager::checkStartStatesOfGroup(
const moveit_msgs::msg::MotionSequenceRequest& req_list,
 
  265                                                  const std::string& group_name)
 
  267   bool first_elem{ 
true };
 
  268   for (
const moveit_msgs::msg::MotionSequenceItem& item : req_list.items)
 
  270     if (item.req.group_name != group_name)
 
  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()))
 
  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());
 
  292 void CommandListManager::checkStartStates(
const moveit_msgs::msg::MotionSequenceRequest& req_list)
 
  294   if (req_list.items.size() <= 1)
 
  299   GroupNamesCont group_names{ getGroupNames(req_list) };
 
  300   for (
const auto& curr_group_name : group_names)
 
  302     checkStartStatesOfGroup(req_list, curr_group_name);
 
  306 CommandListManager::GroupNamesCont
 
  307 CommandListManager::getGroupNames(
const moveit_msgs::msg::MotionSequenceRequest& req_list)
 
  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())
 
  314                     group_names.emplace_back(item.req.group_name);
 
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
 
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 ¶m_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 ¶m_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
 
This namespace includes the central class for representing planning contexts.
 
moveit_msgs::msg::MoveItErrorCodes error_code_