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