moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_component.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, Peter David Fagan
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
35/* Author: Peter David Fagan */
36
38#include <memory>
39
40namespace moveit_py
41{
42namespace bind_planning_component
43{
45plan(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
46 std::shared_ptr<moveit_cpp::PlanningComponent::PlanRequestParameters>& single_plan_parameters,
47 std::shared_ptr<moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters>& multi_plan_parameters,
48 std::shared_ptr<planning_scene::PlanningScene>& planning_scene,
49 std::optional<const moveit::planning_pipeline_interfaces::SolutionSelectionFunction> solution_selection_function,
50 std::optional<moveit::planning_pipeline_interfaces::StoppingCriterionFunction> stopping_criterion_callback)
51{
52 // parameter argument checking
53 if (single_plan_parameters && multi_plan_parameters)
54 {
55 throw std::invalid_argument("Cannot specify both single and multi plan parameters");
56 }
57
58 // check whether single or multi pipeline
59 if (single_plan_parameters)
60 {
61 // cast parameters
62 std::shared_ptr<const moveit_cpp::PlanningComponent::PlanRequestParameters> const_single_plan_parameters =
63 std::const_pointer_cast<const moveit_cpp::PlanningComponent::PlanRequestParameters>(single_plan_parameters);
64
65 return planning_component->plan(*const_single_plan_parameters, planning_scene);
66 }
67 else if (multi_plan_parameters)
68 {
69 // cast parameters
70 std::shared_ptr<const moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters> const_multi_plan_parameters =
71 std::const_pointer_cast<const moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters>(
72 multi_plan_parameters);
73
74 if (solution_selection_function && stopping_criterion_callback)
75 {
76 return planning_component->plan(*const_multi_plan_parameters, std::ref(*solution_selection_function),
77 *stopping_criterion_callback, planning_scene);
78 }
79 else if (solution_selection_function)
80 {
81 return planning_component->plan(*const_multi_plan_parameters, std::ref(*solution_selection_function), nullptr,
83 }
84 else if (stopping_criterion_callback)
85 {
86 return planning_component->plan(*const_multi_plan_parameters,
88 *stopping_criterion_callback, planning_scene);
89 }
90 else
91 {
92 return planning_component->plan(*const_multi_plan_parameters,
95 }
96 }
97 else
98 {
100 {
101 throw std::invalid_argument("Cannot specify planning scene without specifying plan parameters");
102 }
103 return planning_component->plan();
104 }
105}
106
107bool setGoal(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
108 std::optional<std::string> configuration_name, std::optional<moveit::core::RobotState> robot_state,
109 std::optional<geometry_msgs::msg::PoseStamped> pose_stamped_msg, std::optional<std::string> pose_link,
110 std::optional<std::vector<moveit_msgs::msg::Constraints>> motion_plan_constraints)
111{
112 // check that no more than one argument is specified
113 if (configuration_name && robot_state)
114 {
115 throw std::invalid_argument("Cannot specify both configuration name and robot state");
116 }
117 else if (configuration_name && pose_stamped_msg)
118 {
119 throw std::invalid_argument("Cannot specify both configuration name and pose msg");
120 }
121 else if (configuration_name && motion_plan_constraints)
122 {
123 throw std::invalid_argument("Cannot specify both configuration name and motion plan constraints");
124 }
125 else if (robot_state && pose_stamped_msg)
126 {
127 throw std::invalid_argument("Cannot specify both robot state and pose msg");
128 }
129 else if (robot_state && motion_plan_constraints)
130 {
131 throw std::invalid_argument("Cannot specify both robot state and motion plan constraints");
132 }
133 else if (pose_stamped_msg && motion_plan_constraints)
134 {
135 throw std::invalid_argument("Cannot specify both pose goal and motion plan constraints");
136 }
137 else if ((pose_stamped_msg && !pose_link) || (!pose_stamped_msg && pose_link))
138 {
139 throw std::invalid_argument("Must specify both message and corresponding link");
140 }
141
142 // check that at least one argument is specified
143 if (!configuration_name && !robot_state && !pose_stamped_msg && !pose_link && !motion_plan_constraints)
144 {
145 throw std::invalid_argument("Must specify at least one argument");
146 }
147
148 // 1. set goal from configuration name
149 if (configuration_name)
150 {
151 return planning_component->setGoal(*configuration_name);
152 }
153 // 2. set goal from robot_state
154 else if (robot_state)
155 {
156 return planning_component->setGoal(*robot_state);
157 }
158 // 3. set goal from pose_goal
159 else if (pose_stamped_msg && pose_link)
160 {
161 return planning_component->setGoal(*pose_stamped_msg, *pose_link);
162 }
163 // 4. set goal from motion_plan_constraints
164 else
165 {
166 return planning_component->setGoal(*motion_plan_constraints);
167 }
168}
169
170bool setStartState(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
171 std::optional<std::string> configuration_name, std::optional<moveit::core::RobotState> robot_state)
172{
173 // check that no more than one argument is specified
174 if (configuration_name && robot_state)
175 {
176 throw std::invalid_argument("Cannot specify both configuration name and robot state");
177 }
178
179 // check that at least one argument is specified
180 if (!configuration_name && !robot_state)
181 {
182 throw std::invalid_argument("Must specify at least one argument");
183 }
184
185 // 1. set start state from configuration name
186 if (configuration_name)
187 {
188 return planning_component->setStartState(*configuration_name);
189 }
190 // 2. set start state from robot_state
191 else
192 {
193 return planning_component->setStartState(*robot_state);
194 }
195}
196
197void initPlanRequestParameters(py::module& m)
198{
200 std::shared_ptr<moveit_cpp::PlanningComponent::PlanRequestParameters>>(m, "PlanRequestParameters",
201 R"(
202 Planner parameters provided with a MotionPlanRequest.
203 )")
204 .def(py::init([](std::shared_ptr<moveit_cpp::MoveItCpp>& moveit_cpp, const std::string& ns) {
205 const rclcpp::Node::SharedPtr& node = moveit_cpp->getNode();
207 params.load(node, ns);
208 return params;
209 }))
211 R"(
212 str: The planner id to use.
213 )")
215 R"(
216 str: The planning pipeline to use.
217 )")
219 R"(
220 int: The number of planning attempts to make.
221 )")
223 R"(
224 float: The amount of time to spend planning.
225 )")
226 .def_readwrite("max_velocity_scaling_factor",
228 R"(
229 float: The maximum velocity scaling factor that can be used.
230 )")
231 .def_readwrite("max_acceleration_scaling_factor",
233 R"(
234 float: The maximum scaling factor that can be used.
235 )");
236}
237
238void initMultiPlanRequestParameters(py::module& m)
241 std::shared_ptr<moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters>>(
242 m, "MultiPipelinePlanRequestParameters",
243 R"(
244 Planner parameters provided with a MotionPlanRequest.
245 )")
246 .def(py::init([](std::shared_ptr<moveit_cpp::MoveItCpp>& moveit_cpp,
247 const std::vector<std::string>& planning_pipeline_names) {
248 const rclcpp::Node::SharedPtr& node = moveit_cpp->getNode();
249 moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters params{ node, planning_pipeline_names };
250 return params;
251 }))
252 .def_readonly("multi_plan_request_parameters",
254}
255void initPlanningComponent(py::module& m)
256{
257 py::class_<moveit_cpp::PlanningComponent, std::shared_ptr<moveit_cpp::PlanningComponent>>(m, "PlanningComponent",
258 R"(
259 Represents a joint model group and motion plans corresponding to this joint model group.
260 )")
261
262 .def(py::init<const std::string&, const std::shared_ptr<moveit_cpp::MoveItCpp>&>(),
263 py::arg("joint_model_group_name"), py::arg("moveit_py_instance"),
264 R"(
265 Constructs a PlanningComponent instance.
266
267 Args:
268 joint_model_group_name (str): The name of the joint model group to plan for.
269 moveit_py_instance (:py:class:`moveit_py.core.MoveItPy`): The MoveItPy instance to use.
270 )")
271
272 .def("get_named_target_state_values", &moveit_cpp::PlanningComponent::getNamedTargetStateValues, py::arg("name"),
273 R"(
274 dict: The joint values for targets specified by name.
275 )")
276
277 .def_property("planning_group_name", &moveit_cpp::PlanningComponent::getPlanningGroupName, nullptr,
278 R"(
279 str: The name of the planning group to plan for.
280 )")
281
282 .def_property("named_target_states", &moveit_cpp::PlanningComponent::getNamedTargetStates, nullptr,
283 R"(
284 list of str: The names of the named robot states available as targets.
285 )")
286
287 // start state methods
288 .def("set_start_state_to_current_state", &moveit_cpp::PlanningComponent::setStartStateToCurrentState,
289 R"(
290 Set the start state of the plan to the current state of the robot.
291 )")
292
294 py::arg("configuration_name") = nullptr, py::arg("robot_state") = nullptr,
295 R"(
296 Set the start state of the plan to the given robot state.
297
298 Args:
299 configuration_name (str): The name of the configuration to use as the start state.
300 robot_state (:py:class:`moveit_msgs.msg.RobotState`): The robot state to use as the start state.
301 )")
302
303 .def("get_start_state", &moveit_cpp::PlanningComponent::getStartState,
304 py::return_value_policy::reference_internal,
305 R"(
306 Returns the current start state for the planning component.
307 )")
308
309 // goal state methods
310 .def("set_goal_state",
311 py::overload_cast<std::shared_ptr<moveit_cpp::PlanningComponent>&, std::optional<std::string>,
312 std::optional<moveit::core::RobotState>, std::optional<geometry_msgs::msg::PoseStamped>,
313 std::optional<std::string>, std::optional<std::vector<moveit_msgs::msg::Constraints>>>(
315 py::arg("configuration_name") = nullptr, py::arg("robot_state") = nullptr,
316 py::arg("pose_stamped_msg") = nullptr, py::arg("pose_link") = nullptr,
317 py::arg("motion_plan_constraints") = nullptr,
318 R"(
319 Set the goal state for the planning component.
320
321 Args:
322 configuration_name (str): The name of the configuration to set the goal to.
323 robot_state (moveit_py.core.RobotState): The state to set the goal to.
324 pose_stamped_msg (geometry_msgs.msg.PoseStamped): A PoseStamped ros message.
325 pose_link (str): The name of the link for which the pose constraint is specified.
326 motion_plan_constraints (list): The motion plan constraints to set the goal to.
327 )")
328
329 // plan/execution methods
330
331 // TODO (peterdavidfagan): improve the plan API
332 .def("plan", &moveit_py::bind_planning_component::plan, py::arg("single_plan_parameters") = nullptr,
333 py::arg("multi_plan_parameters") = nullptr, py::arg("planning_scene") = nullptr,
334 py::arg("solution_selection_function") = nullptr, py::arg("stopping_criterion_callback") = nullptr,
335 py::return_value_policy::move,
336 R"(
337 Plan a motion plan using the current start and goal states.
338
339 Args:
340 plan_parameters (moveit_py.core.PlanParameters): The parameters to use for planning.
341 )")
342
343 .def("set_path_constraints", &moveit_cpp::PlanningComponent::setPathConstraints, py::arg("path_constraints"),
344 py::return_value_policy::move,
345 R"(
346 Set the path constraints generated from a moveit msg Constraints.
347
348 Args:
349 path_constraints (moveit_msgs.msg.Constraints): The path constraints.
350 )")
351
352 // Interacting with workspace
353 .def("set_workspace", &moveit_cpp::PlanningComponent::setWorkspace, py::arg("min_x"), py::arg("min_y"),
354 py::arg("min_z"), py::arg("max_x"), py::arg("max_y"), py::arg("max_z"),
355 R"(
356 Specify the workspace bounding box. The box is specified in the planning frame (i.e. relative to the robot root link start position). The workspace applies only to the root joint of a mobile robot (driving base, quadrotor) and does not limit the workspace of a robot arm.
357
358 Args:
359 min_x (float): The minimum x value of the workspace.
360 min_y (float): The minimum y value of the workspace.
361 min_z (float): The minimum z value of the workspace.
362 max_x (float): The maximum x value of the workspace.
363 max_y (float): The maximum y value of the workspace.
364 max_z (float): The maximum z value of the workspace.
365 )")
366
367 .def("unset_workspace", &moveit_cpp::PlanningComponent::unsetWorkspace,
368 R"(
369 Remove the workspace bounding box from planning.
370 )");
371}
372} // namespace bind_planning_component
373} // namespace moveit_py
void setStartStateToCurrentState()
Set the start state for planning to be the current state of the robot.
std::map< std::string, double > getNamedTargetStateValues(const std::string &name)
Get the joint values for targets specified by name.
void unsetWorkspace()
Remove the workspace bounding box from planning.
const std::string & getPlanningGroupName() const
Get the name of the planning group.
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Specify the workspace bounding box. The box is specified in the planning frame (i....
bool setPathConstraints(const moveit_msgs::msg::Constraints &path_constraints)
Set the path constraints generated from a moveit msg Constraints.
const std::vector< std::string > getNamedTargetStates()
Get the names of the named robot states available as targets.
moveit::core::RobotStatePtr getStartState()
Get the considered start state if defined, otherwise get the current state.
::planning_interface::MotionPlanResponse getShortestSolution(const std::vector<::planning_interface::MotionPlanResponse > &solutions)
Function that returns the shortest solution out of a vector of solutions based on robot_trajectory::p...
bool setStartState(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::optional< std::string > configuration_name, std::optional< moveit::core::RobotState > robot_state)
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
bool setGoal(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::optional< std::string > configuration_name, std::optional< moveit::core::RobotState > robot_state, std::optional< geometry_msgs::msg::PoseStamped > pose_stamped_msg, std::optional< std::string > pose_link, std::optional< std::vector< moveit_msgs::msg::Constraints > > motion_plan_constraints)
This namespace includes the central class for representing planning contexts.
Planner parameters provided with the MotionPlanRequest.
Planner parameters provided with the MotionPlanRequest.
void load(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace="")