Program Listing for File command_list_manager.h

Return to documentation for file (include/pilz_industrial_motion_planner/command_list_manager.h)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2018 Pilz GmbH & Co. KG
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of Pilz GmbH & Co. KG nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *********************************************************************/

#pragma once

#include <string>

#include <memory>
#include <functional>

#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit_msgs/msg/motion_plan_response.hpp>
#include <moveit_msgs/msg/motion_sequence_request.hpp>

#include <pilz_industrial_motion_planner/plan_components_builder.h>
#include <pilz_industrial_motion_planner/trajectory_blender.h>
#include <pilz_industrial_motion_planner/trajectory_generation_exceptions.h>

#include <cartesian_limits_parameters.hpp>

namespace pilz_industrial_motion_planner
{
using RobotTrajCont = std::vector<robot_trajectory::RobotTrajectoryPtr>;

// List of exceptions which can be thrown by the CommandListManager class.
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException,
                                   moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(LastBlendRadiusNotZeroException,
                                   moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(StartStateSetException, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OverlappingBlendRadiiException,
                                   moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PlanningPipelineException, moveit_msgs::msg::MoveItErrorCodes::FAILURE);

class CommandListManager
{
public:
  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);

private:
  using MotionResponseCont = std::vector<planning_interface::MotionPlanResponse>;
  using RobotState_OptRef = const std::optional<std::reference_wrapper<const moveit::core::RobotState>>;
  using RadiiCont = std::vector<double>;
  using GroupNamesCont = std::vector<std::string>;

private:
  void checkForOverlappingRadii(const MotionResponseCont& resp_cont, const RadiiCont& radii) const;

  MotionResponseCont solveSequenceItems(const planning_scene::PlanningSceneConstPtr& planning_scene,
                                        const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
                                        const moveit_msgs::msg::MotionSequenceRequest& req_list) const;

  bool checkRadiiForOverlap(const robot_trajectory::RobotTrajectory& traj_A, const double radii_A,
                            const robot_trajectory::RobotTrajectory& traj_B, const double radii_B) const;

private:
  static RobotState_OptRef getPreviousEndState(const MotionResponseCont& motion_plan_responses,
                                               const std::string& group_name);

  static void setStartState(const MotionResponseCont& motion_plan_responses, const std::string& group_name,
                            moveit_msgs::msg::RobotState& start_state);

  static RadiiCont extractBlendRadii(const moveit::core::RobotModel& model,
                                     const moveit_msgs::msg::MotionSequenceRequest& req_list);

  static bool isInvalidBlendRadii(const moveit::core::RobotModel& model,
                                  const moveit_msgs::msg::MotionSequenceItem& item_A,
                                  const moveit_msgs::msg::MotionSequenceItem& item_B);

  static void checkForNegativeRadii(const moveit_msgs::msg::MotionSequenceRequest& req_list);

  static void checkLastBlendRadiusZero(const moveit_msgs::msg::MotionSequenceRequest& req_list);

  static void checkStartStatesOfGroup(const moveit_msgs::msg::MotionSequenceRequest& req_list,
                                      const std::string& group_name);

  static void checkStartStates(const moveit_msgs::msg::MotionSequenceRequest& req_list);

  static GroupNamesCont getGroupNames(const moveit_msgs::msg::MotionSequenceRequest& req_list);

private:
  const rclcpp::Node::SharedPtr node_;

  moveit::core::RobotModelConstPtr model_;

  PlanComponentsBuilder plan_comp_builder_;

  std::shared_ptr<cartesian_limits::ParamListener> param_listener_;
  cartesian_limits::Params params_;
};

inline void CommandListManager::checkLastBlendRadiusZero(const moveit_msgs::msg::MotionSequenceRequest& req_list)
{
  if (req_list.items.back().blend_radius != 0.0)
  {
    throw LastBlendRadiusNotZeroException("The last blending radius must be zero");
  }
}

}  // namespace pilz_industrial_motion_planner