moveit2
The MoveIt Motion Planning Framework for ROS 2.
moveit_planning_pipeline.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik 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 PickNik Inc. 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 
38 
39 namespace
40 {
41 const rclcpp::Logger LOGGER = rclcpp::get_logger("global_planner_component");
42 }
43 
45 {
46 const std::string PLANNING_SCENE_MONITOR_NS = "planning_scene_monitor_options.";
47 const std::string PLANNING_PIPELINES_NS = "planning_pipelines.";
48 const std::string PLAN_REQUEST_PARAM_NS = "plan_request_params.";
49 const std::string UNDEFINED = "<undefined>";
50 
51 bool MoveItPlanningPipeline::initialize(const rclcpp::Node::SharedPtr& node)
52 {
53  // TODO(andyz): how to standardize this for planning pipelines other than ompl?
54  // Maybe use loadPlanningPipelines() from moveit_cpp.cpp
55 
56  // Declare planning pipeline parameter
57  node->declare_parameter<std::vector<std::string>>(PLANNING_PIPELINES_NS + "pipeline_names",
58  std::vector<std::string>({ UNDEFINED }));
59  node->declare_parameter<std::string>(PLANNING_PIPELINES_NS + "namespace", UNDEFINED);
60 
61  // Default PlanRequestParameters. These can be overridden when plan() is called
62  node->declare_parameter<std::string>(PLAN_REQUEST_PARAM_NS + "planner_id", UNDEFINED);
63  node->declare_parameter<std::string>(PLAN_REQUEST_PARAM_NS + "planning_pipeline", UNDEFINED);
64  node->declare_parameter<int>(PLAN_REQUEST_PARAM_NS + "planning_attempts", 5);
65  node->declare_parameter<double>(PLAN_REQUEST_PARAM_NS + "planning_time", 1.0);
66  node->declare_parameter<double>(PLAN_REQUEST_PARAM_NS + "max_velocity_scaling_factor", 1.0);
67  node->declare_parameter<double>(PLAN_REQUEST_PARAM_NS + "max_acceleration_scaling_factor", 1.0);
68  node->declare_parameter<std::string>("ompl.planning_plugin", "ompl_interface/OMPLPlanner");
69 
70  // Planning Scene options
71  node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "name", UNDEFINED);
72  node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "robot_description", UNDEFINED);
73  node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "joint_state_topic", UNDEFINED);
74  node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "attached_collision_object_topic", UNDEFINED);
75  node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "publish_planning_scene_topic", UNDEFINED);
76  node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "monitored_planning_scene_topic", UNDEFINED);
77  node->declare_parameter<double>(PLANNING_SCENE_MONITOR_NS + "wait_for_initial_state_timeout", 10.0);
78 
79  // Trajectory Execution Functionality (required by the MoveItPlanningPipeline but not used within hybrid planning)
80  node->declare_parameter<std::string>("moveit_controller_manager", UNDEFINED);
81 
82  node_ptr_ = node;
83 
84  // Initialize MoveItCpp API
85  moveit_cpp::MoveItCpp::Options moveit_cpp_options(node);
86  moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(node, moveit_cpp_options);
87 
88  return true;
89 }
90 
92 {
93  // Do Nothing
94  return true;
95 }
96 
97 moveit_msgs::msg::MotionPlanResponse MoveItPlanningPipeline::plan(
98  const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::GlobalPlanner>> global_goal_handle)
99 {
100  moveit_msgs::msg::MotionPlanResponse response;
101 
102  if ((global_goal_handle->get_goal())->motion_sequence.items.empty())
103  {
104  RCLCPP_WARN(LOGGER, "Global planner received motion sequence request with no items. At least one is needed.");
105  response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
106  return response;
107  }
108 
109  // Process goal
110  if ((global_goal_handle->get_goal())->motion_sequence.items.size() > 1)
111  {
112  RCLCPP_WARN(LOGGER, "Global planner received motion sequence request with more than one item but the "
113  "'moveit_planning_pipeline' plugin only accepts one item. Just using the first item as global "
114  "planning goal!");
115  }
116  auto motion_plan_req = (global_goal_handle->get_goal())->motion_sequence.items[0].req;
117 
118  // Set parameters required by the planning component
120  plan_params.planner_id = motion_plan_req.planner_id;
121  plan_params.planning_pipeline = motion_plan_req.pipeline_id;
122  plan_params.planning_attempts = motion_plan_req.num_planning_attempts;
123  plan_params.planning_time = motion_plan_req.allowed_planning_time;
124  plan_params.max_velocity_scaling_factor = motion_plan_req.max_velocity_scaling_factor;
125  plan_params.max_acceleration_scaling_factor = motion_plan_req.max_acceleration_scaling_factor;
126 
127  // Create planning component
128  auto planning_components = std::make_shared<moveit_cpp::PlanningComponent>(motion_plan_req.group_name, moveit_cpp_);
129 
130  // Copy goal constraint into planning component
131  planning_components->setGoal(motion_plan_req.goal_constraints);
132 
133  // Plan motion
134  auto plan_solution = planning_components->plan(plan_params);
135  if (plan_solution.error_code != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
136  {
137  response.error_code = plan_solution.error_code;
138  return response;
139  }
140 
141  // Transform solution into MotionPlanResponse and publish it
142  response.trajectory_start = plan_solution.start_state;
143  response.group_name = motion_plan_req.group_name;
144  plan_solution.trajectory->getRobotTrajectoryMsg(response.trajectory);
145  response.error_code = plan_solution.error_code;
146 
147  return response;
148 }
149 } // namespace moveit::hybrid_planning
150 
151 #include <pluginlib/class_list_macros.hpp>
152 
moveit_msgs::msg::MotionPlanResponse plan(const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >> global_goal_handle) override
bool initialize(const rclcpp::Node::SharedPtr &node) override
PLUGINLIB_EXPORT_CLASS(moveit::hybrid_planning::MoveItPlanningPipeline, moveit::hybrid_planning::GlobalPlannerInterface)
const std::string PLANNING_SCENE_MONITOR_NS
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Parameter container for initializing MoveItCpp.
Definition: moveit_cpp.h:99
Planner parameters provided with the MotionPlanRequest.