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) 2019, 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
35/* Author: Henning Kayser */
36
37#include <stdexcept>
38
44#include <thread>
46
47namespace moveit_cpp
48{
49
50PlanningComponent::PlanningComponent(const std::string& group_name, const MoveItCppPtr& moveit_cpp)
51 : node_(moveit_cpp->getNode())
52 , moveit_cpp_(moveit_cpp)
53 , group_name_(group_name)
54 , logger_(moveit::getLogger("moveit.ros.planning_component"))
55{
56 joint_model_group_ = moveit_cpp_->getRobotModel()->getJointModelGroup(group_name);
57 if (!joint_model_group_)
58 {
59 std::string error = "Could not find joint model group '" + group_name + "'.";
60 RCLCPP_FATAL_STREAM(logger_, error);
61 throw std::runtime_error(error);
62 }
63}
64
65PlanningComponent::PlanningComponent(const std::string& group_name, const rclcpp::Node::SharedPtr& node)
66 : PlanningComponent(group_name, std::make_shared<MoveItCpp>(node))
67{
68 joint_model_group_ = moveit_cpp_->getRobotModel()->getJointModelGroup(group_name);
69 if (!joint_model_group_)
70 {
71 std::string error = "Could not find joint model group '" + group_name + "'.";
72 RCLCPP_FATAL_STREAM(logger_, error);
73 throw std::runtime_error(error);
74 }
75}
76
77const std::vector<std::string> PlanningComponent::getNamedTargetStates()
78{
79 if (joint_model_group_)
80 {
81 return joint_model_group_->getDefaultStateNames();
82 }
83 else
84 {
85 RCLCPP_WARN(logger_, "Unable to find joint group with name '%s'.", group_name_.c_str());
86 }
87
88 std::vector<std::string> empty;
89 return empty;
90}
91
93{
94 return group_name_;
95}
96
97bool PlanningComponent::setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints)
98{
99 current_path_constraints_ = path_constraints;
100 return true;
101}
102
103bool PlanningComponent::setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints& trajectory_constraints)
104{
105 current_trajectory_constraints_ = trajectory_constraints;
106 return true;
107}
108
110 planning_scene::PlanningScenePtr planning_scene)
111{
112 auto plan_solution = planning_interface::MotionPlanResponse();
113
114 // check if joint_model_group exists
115 if (!joint_model_group_)
116 {
117 RCLCPP_ERROR(logger_, "Failed to retrieve joint model group for name '%s'.", group_name_.c_str());
118 plan_solution.error_code = moveit::core::MoveItErrorCode::INVALID_GROUP_NAME;
119 return plan_solution;
120 }
121
122 // Check if goal constraints exist
123 if (current_goal_constraints_.empty())
124 {
125 RCLCPP_ERROR(logger_, "No goal constraints set for planning request");
126 plan_solution.error_code = moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS;
127 return plan_solution;
128 }
129
130 if (!planning_scene)
131 { // Clone current planning scene
132 auto planning_scene_monitor = moveit_cpp_->getPlanningSceneMonitorNonConst();
133 planning_scene_monitor->updateFrameTransforms();
137 }();
138 planning_scene_monitor.reset(); // release this pointer}
139 }
140 // Init MotionPlanRequest
142
143 // Set start state
144 planning_scene->setCurrentState(request.start_state);
145
146 // Run planning attempt
148 moveit_cpp_->getPlanningPipelines());
149}
150
152 const MultiPipelinePlanRequestParameters& parameters,
155 planning_scene::PlanningScenePtr planning_scene)
156{
157 auto plan_solution = planning_interface::MotionPlanResponse();
158
159 // check if joint_model_group exists
160 if (!joint_model_group_)
161 {
162 RCLCPP_ERROR(logger_, "Failed to retrieve joint model group for name '%s'.", group_name_.c_str());
163 plan_solution.error_code = moveit::core::MoveItErrorCode::INVALID_GROUP_NAME;
164 return plan_solution;
165 }
166
167 // Check if goal constraints exist
168 if (current_goal_constraints_.empty())
169 {
170 RCLCPP_ERROR(logger_, "No goal constraints set for planning request");
171 plan_solution.error_code = moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS;
172 return plan_solution;
173 }
174
175 if (!planning_scene)
176 { // Clone current planning scene
177 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor =
178 moveit_cpp_->getPlanningSceneMonitorNonConst();
179 planning_scene_monitor->updateFrameTransforms();
183 }();
184 planning_scene_monitor.reset(); // release this pointer}
185 }
186 // Init MotionPlanRequest
187 std::vector<::planning_interface::MotionPlanRequest> requests = getMotionPlanRequestVector(parameters);
188
189 // Set start state
190 for (const auto& request : requests)
191 {
192 planning_scene->setCurrentState(request.start_state);
193 }
194
195 const auto motion_plan_response_vector = moveit::planning_pipeline_interfaces::planWithParallelPipelines(
196 requests, planning_scene, moveit_cpp_->getPlanningPipelines(), stopping_criterion_callback,
197 solution_selection_function);
198
199 try
200 {
201 // If a solution_selection function is passed to the parallel pipeline interface, the returned vector contains only
202 // the selected solution
203 plan_solution = motion_plan_response_vector.at(0);
204 }
205 catch (std::out_of_range&)
206 {
207 RCLCPP_ERROR(logger_, "MotionPlanResponse vector was empty after parallel planning");
208 plan_solution.error_code = moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS;
209 }
210 // Run planning attempt
211 return plan_solution;
212}
213
215{
216 PlanRequestParameters plan_request_parameters;
217 plan_request_parameters.load(node_);
218 RCLCPP_DEBUG_STREAM(
219 logger_, "Default plan request parameters loaded with --"
220 << " planning_pipeline: " << plan_request_parameters.planning_pipeline << ','
221 << " planner_id: " << plan_request_parameters.planner_id << ','
222 << " planning_time: " << plan_request_parameters.planning_time << ','
223 << " planning_attempts: " << plan_request_parameters.planning_attempts << ','
224 << " max_velocity_scaling_factor: " << plan_request_parameters.max_velocity_scaling_factor << ','
225 << " max_acceleration_scaling_factor: " << plan_request_parameters.max_acceleration_scaling_factor);
226 return plan(plan_request_parameters);
227}
228
230{
231 considered_start_state_ = std::make_shared<moveit::core::RobotState>(start_state);
232 return true;
233}
234
235moveit::core::RobotStatePtr PlanningComponent::getStartState()
236{
237 if (considered_start_state_)
238 {
239 return considered_start_state_;
240 }
241 else
242 {
243 moveit::core::RobotStatePtr s;
244 moveit_cpp_->getCurrentState(s, 1.0);
245 return s;
246 }
247}
248
249bool PlanningComponent::setStartState(const std::string& start_state_name)
250{
251 const auto& named_targets = getNamedTargetStates();
252 if (std::find(named_targets.begin(), named_targets.end(), start_state_name) == named_targets.end())
253 {
254 RCLCPP_ERROR(logger_, "No predefined joint state found for target name '%s'", start_state_name.c_str());
255 return false;
256 }
257 moveit::core::RobotState start_state(moveit_cpp_->getRobotModel());
258 start_state.setToDefaultValues(); // required to ensure all joints are initialized
259 start_state.setToDefaultValues(joint_model_group_, start_state_name);
260 return setStartState(start_state);
261}
262
264{
265 considered_start_state_.reset();
266}
267
268std::map<std::string, double> PlanningComponent::getNamedTargetStateValues(const std::string& name)
269{
270 // TODO(henningkayser): verify result
271 std::map<std::string, double> positions;
272 joint_model_group_->getVariableDefaultPositions(name, positions);
273 return positions;
274}
275
276void PlanningComponent::setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
277{
278 workspace_parameters_.header.frame_id = moveit_cpp_->getRobotModel()->getModelFrame();
279 workspace_parameters_.header.stamp = node_->now();
280 workspace_parameters_.min_corner.x = minx;
281 workspace_parameters_.min_corner.y = miny;
282 workspace_parameters_.min_corner.z = minz;
283 workspace_parameters_.max_corner.x = maxx;
284 workspace_parameters_.max_corner.y = maxy;
285 workspace_parameters_.max_corner.z = maxz;
286 workspace_parameters_set_ = true;
287}
288
290{
291 workspace_parameters_set_ = false;
292}
293
294bool PlanningComponent::setGoal(const std::vector<moveit_msgs::msg::Constraints>& goal_constraints)
295{
296 current_goal_constraints_ = goal_constraints;
297 return true;
298}
299
301{
302 current_goal_constraints_ = { kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group_) };
303 return true;
304}
305
306bool PlanningComponent::setGoal(const geometry_msgs::msg::PoseStamped& goal_pose, const std::string& link_name)
307{
308 current_goal_constraints_ = { kinematic_constraints::constructGoalConstraints(link_name, goal_pose) };
309 return true;
310}
311
312bool PlanningComponent::setGoal(const std::string& goal_state_name)
313{
314 const auto& named_targets = getNamedTargetStates();
315 if (std::find(named_targets.begin(), named_targets.end(), goal_state_name) == named_targets.end())
316 {
317 RCLCPP_ERROR(logger_, "No predefined joint state found for target name '%s'", goal_state_name.c_str());
318 return false;
319 }
320 moveit::core::RobotState goal_state(moveit_cpp_->getRobotModel());
321 goal_state.setToDefaultValues(joint_model_group_, goal_state_name);
322 return setGoal(goal_state);
323}
324
327{
329 request.group_name = group_name_;
330 request.pipeline_id = plan_request_parameters.planning_pipeline;
331 request.planner_id = plan_request_parameters.planner_id;
332 request.num_planning_attempts = std::max(1, plan_request_parameters.planning_attempts);
333 request.allowed_planning_time = plan_request_parameters.planning_time;
334 request.max_velocity_scaling_factor = plan_request_parameters.max_velocity_scaling_factor;
335 request.max_acceleration_scaling_factor = plan_request_parameters.max_acceleration_scaling_factor;
336 if (workspace_parameters_set_)
337 {
338 request.workspace_parameters = workspace_parameters_;
339 }
340 request.goal_constraints = current_goal_constraints_;
341 request.path_constraints = current_path_constraints_;
342 request.trajectory_constraints = current_trajectory_constraints_;
343
344 // Set start state
345 moveit::core::RobotStatePtr start_state = considered_start_state_;
346 if (!start_state)
347 {
348 start_state = moveit_cpp_->getCurrentState();
349 }
350 start_state->update();
351 moveit::core::robotStateToRobotStateMsg(*start_state, request.start_state);
352 return request;
353}
354
355std::vector<::planning_interface::MotionPlanRequest> PlanningComponent::getMotionPlanRequestVector(
356 const MultiPipelinePlanRequestParameters& multi_pipeline_plan_request_parameters)
357{
358 std::vector<::planning_interface::MotionPlanRequest> motion_plan_requests;
359 motion_plan_requests.reserve(multi_pipeline_plan_request_parameters.plan_request_parameter_vector.size());
360 for (const auto& plan_request_parameters : multi_pipeline_plan_request_parameters.plan_request_parameter_vector)
361 {
362 motion_plan_requests.push_back(getMotionPlanRequest(plan_request_parameters));
363 }
364 return motion_plan_requests;
365}
366} // namespace moveit_cpp
bool getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const
Get the values that correspond to a named state as read from the URDF. Return false on failure.
const std::vector< std::string > & getDefaultStateNames() const
Get the names of the known default states (as specified in the SRDF)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void setStartStateToCurrentState()
Set the start state for planning to be the current state of the robot.
bool setStartState(const moveit::core::RobotState &start_state)
Set the robot state that should be considered as start state for planning.
std::map< std::string, double > getNamedTargetStateValues(const std::string &name)
Get the joint values for targets specified by name.
planning_interface::MotionPlanResponse plan()
Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() usi...
void unsetWorkspace()
Remove the workspace bounding box from planning.
bool setGoal(const std::vector< moveit_msgs::msg::Constraints > &goal_constraints)
Set the goal constraints used for planning.
const std::string & getPlanningGroupName() const
Get the name of the planning group.
::planning_interface::MotionPlanRequest getMotionPlanRequest(const PlanRequestParameters &plan_request_parameters)
Utility function to get a MotionPlanRequest from PlanRequestParameters and the internal state of the ...
bool setTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &trajectory_constraints)
Set the trajectory constraints generated from a moveit msg Constraints.
PlanningComponent(const std::string &group_name, const rclcpp::Node::SharedPtr &node)
Constructor.
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.
std::vector<::planning_interface::MotionPlanRequest > getMotionPlanRequestVector(const MultiPipelinePlanRequestParameters &multi_pipeline_plan_request_parameters)
Utility function to get a Vector of MotionPlanRequest from a vector of PlanRequestParameters and the ...
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.
static PlanningScenePtr clone(const PlanningSceneConstPtr &scene)
Clone a planning scene. Even if the scene scene depends on a parent, the cloned scene will not.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition utils.cpp:152
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.
::planning_interface::MotionPlanResponse planWithSinglePipeline(const ::planning_interface::MotionPlanRequest &motion_plan_request, const ::planning_scene::PlanningSceneConstPtr &planning_scene, const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > &planning_pipelines)
Function to calculate the MotionPlanResponse for a given MotionPlanRequest and a PlanningScene.
std::function< bool(const PlanResponsesContainer &plan_responses_container, const std::vector<::planning_interface::MotionPlanRequest > &plan_requests)> StoppingCriterionFunction
A stopping criterion callback function for the parallel planning API of planning component.
const std::vector<::planning_interface::MotionPlanResponse > planWithParallelPipelines(const std::vector<::planning_interface::MotionPlanRequest > &motion_plan_requests, const ::planning_scene::PlanningSceneConstPtr &planning_scene, const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > &planning_pipelines, const StoppingCriterionFunction &stopping_criterion_callback=nullptr, const SolutionSelectionFunction &solution_selection_function=nullptr)
Function to solve multiple planning problems in parallel threads with multiple planning pipelines at ...
std::function<::planning_interface::MotionPlanResponse(const std::vector<::planning_interface::MotionPlanResponse > &solutions)> SolutionSelectionFunction
A solution callback function type for the parallel planning API of planning component.
Main namespace for MoveIt.
Definition exceptions.h:43
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
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="")
Response to a planning query.