37
37
38
38
#pragma once
39
39
40
- #include < rclcpp/rclcpp.hpp>
41
- #include < moveit/moveit_cpp/moveit_cpp.h>
42
- #include < moveit/robot_state/robot_state.h>
43
40
#include < geometry_msgs/msg/pose_stamped.h>
41
+ #include < moveit/moveit_cpp/moveit_cpp.h>
42
+ #include < moveit/moveit_cpp/plan_solutions.hpp>
43
+ #include < moveit/planning_interface/planning_response.h>
44
44
#include < moveit/robot_state/conversions.h>
45
+ #include < moveit/robot_state/robot_state.h>
45
46
#include < moveit/utils/moveit_error_code.h>
47
+ #include < rclcpp/rclcpp.hpp>
46
48
47
49
namespace moveit_cpp
48
50
{
49
51
MOVEIT_CLASS_FORWARD (PlanningComponent); // Defines PlanningComponentPtr, ConstPtr, WeakPtr... etc
50
-
51
52
class PlanningComponent
52
53
{
53
54
public:
54
- MOVEIT_STRUCT_FORWARD (PlanSolution);
55
-
56
55
using MoveItErrorCode [[deprecated(" Use moveit::core::MoveItErrorCode" )]] = moveit::core::MoveItErrorCode;
57
-
58
- // / The representation of a plan solution
59
- struct PlanSolution
60
- {
61
- // / The full starting state used for planning
62
- moveit_msgs::msg::RobotState start_state;
63
-
64
- // / The trajectory of the robot (may not contain joints that are the same as for the start_state_)
65
- robot_trajectory::RobotTrajectoryPtr trajectory;
66
-
67
- // / Reason why the plan failed
68
- moveit::core::MoveItErrorCode error_code;
69
-
70
- explicit operator bool () const
71
- {
72
- return bool (error_code);
73
- }
74
- };
75
-
76
56
// / Planner parameters provided with the MotionPlanRequest
77
57
struct PlanRequestParameters
78
58
{
@@ -83,18 +63,67 @@ class PlanningComponent
83
63
double max_velocity_scaling_factor;
84
64
double max_acceleration_scaling_factor;
85
65
86
- void load (const rclcpp::Node::SharedPtr& node)
66
+ template <typename T>
67
+ void declareOrGetParam (const rclcpp::Node::SharedPtr& node, const std::string& param_name, T& output_value,
68
+ T default_value)
69
+ {
70
+ // Try to get parameter or use default
71
+ if (!node->get_parameter_or (param_name, output_value, default_value))
72
+ {
73
+ RCLCPP_WARN (node->get_logger (),
74
+ " Parameter \' %s\' not found in config use default value instead, check parameter type and "
75
+ " namespace in YAML file" ,
76
+ (param_name).c_str ());
77
+ }
78
+ }
79
+
80
+ void load (const rclcpp::Node::SharedPtr& node, const std::string& param_namespace = " " )
87
81
{
82
+ // Set namespace
88
83
std::string ns = " plan_request_params." ;
89
- node->get_parameter_or (ns + " planner_id" , planner_id, std::string (" " ));
90
- node->get_parameter_or (ns + " planning_pipeline" , planning_pipeline, std::string (" " ));
91
- node->get_parameter_or (ns + " planning_time" , planning_time, 1.0 );
92
- node->get_parameter_or (ns + " planning_attempts" , planning_attempts, 5 );
93
- node->get_parameter_or (ns + " max_velocity_scaling_factor" , max_velocity_scaling_factor, 1.0 );
94
- node->get_parameter_or (ns + " max_acceleration_scaling_factor" , max_acceleration_scaling_factor, 1.0 );
84
+ if (!param_namespace.empty ())
85
+ {
86
+ ns = param_namespace + " .plan_request_params." ;
87
+ }
88
+
89
+ // Declare parameters
90
+ declareOrGetParam<std::string>(node, ns + " planner_id" , planner_id, std::string (" " ));
91
+ declareOrGetParam<std::string>(node, ns + " planning_pipeline" , planning_pipeline, std::string (" " ));
92
+ declareOrGetParam<double >(node, ns + " planning_time" , planning_time, 1.0 );
93
+ declareOrGetParam<int >(node, ns + " planning_attempts" , planning_attempts, 5 );
94
+ declareOrGetParam<double >(node, ns + " max_velocity_scaling_factor" , max_velocity_scaling_factor, 1.0 );
95
+ declareOrGetParam<double >(node, ns + " max_acceleration_scaling_factor" , max_acceleration_scaling_factor, 1.0 );
95
96
}
96
97
};
97
98
99
+ // / Planner parameters provided with the MotionPlanRequest
100
+ struct MultiPipelinePlanRequestParameters
101
+ {
102
+ MultiPipelinePlanRequestParameters (const rclcpp::Node::SharedPtr& node,
103
+ const std::vector<std::string>& planning_pipeline_names)
104
+ {
105
+ multi_plan_request_parameters.reserve (planning_pipeline_names.size ());
106
+
107
+ for (const auto & planning_pipeline_name : planning_pipeline_names)
108
+ {
109
+ PlanRequestParameters parameters;
110
+ parameters.load (node, planning_pipeline_name);
111
+ multi_plan_request_parameters.push_back (parameters);
112
+ }
113
+ }
114
+ // Plan request parameters for the individual planning pipelines which run concurrently
115
+ std::vector<PlanRequestParameters> multi_plan_request_parameters;
116
+ };
117
+
118
+ /* * \brief A solution callback function type for the parallel planning API of planning component */
119
+ typedef std::function<planning_interface::MotionPlanResponse(
120
+ const std::vector<planning_interface::MotionPlanResponse>& solutions)>
121
+ SolutionCallbackFunction;
122
+ /* * \brief A stopping criterion callback function for the parallel planning API of planning component */
123
+ typedef std::function<bool (const PlanSolutions& solutions,
124
+ const MultiPipelinePlanRequestParameters& plan_request_parameters)>
125
+ StoppingCriterionFunction;
126
+
98
127
/* * \brief Constructor */
99
128
PlanningComponent (const std::string& group_name, const rclcpp::Node::SharedPtr& node);
100
129
PlanningComponent (const std::string& group_name, const MoveItCppPtr& moveit_cpp);
@@ -154,19 +183,29 @@ class PlanningComponent
154
183
/* * \brief Set the path constraints generated from a moveit msg Constraints */
155
184
bool setPathConstraints (const moveit_msgs::msg::Constraints& path_constraints);
156
185
186
+ /* * \brief Set the trajectory constraints generated from a moveit msg Constraints */
187
+ bool setTrajectoryConstraints (const moveit_msgs::msg::TrajectoryConstraints& trajectory_constraints);
188
+
157
189
/* * \brief Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using
158
190
* default parameters. */
159
- PlanSolution plan ();
191
+ planning_interface::MotionPlanResponse plan ();
192
+ /* * \brief Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the
193
+ * provided PlanRequestParameters. */
194
+ planning_interface::MotionPlanResponse plan (const PlanRequestParameters& parameters, const bool store_solution = true );
195
+
160
196
/* * \brief Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the
161
197
* provided PlanRequestParameters. */
162
- PlanSolution plan (const PlanRequestParameters& parameters);
198
+ planning_interface::MotionPlanResponse
199
+ plan (const MultiPipelinePlanRequestParameters& parameters,
200
+ SolutionCallbackFunction solution_selection_callback = &getShortestSolution,
201
+ StoppingCriterionFunction stopping_criterion_callback = nullptr );
163
202
164
203
/* * \brief Execute the latest computed solution trajectory computed by plan(). By default this function terminates
165
204
* after the execution is complete. The execution can be run in background by setting blocking to false. */
166
205
bool execute (bool blocking = true );
167
206
168
207
/* * \brief Return the last plan solution*/
169
- const PlanSolutionPtr getLastPlanSolution ();
208
+ const planning_interface::MotionPlanResponse& getLastMotionPlanResponse ();
170
209
171
210
private:
172
211
// Core properties and instances
@@ -182,10 +221,11 @@ class PlanningComponent
182
221
moveit::core::RobotStatePtr considered_start_state_;
183
222
std::vector<moveit_msgs::msg::Constraints> current_goal_constraints_;
184
223
moveit_msgs::msg::Constraints current_path_constraints_;
224
+ moveit_msgs::msg::TrajectoryConstraints current_trajectory_constraints_;
185
225
PlanRequestParameters plan_request_parameters_;
186
226
moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
187
227
bool workspace_parameters_set_ = false ;
188
- PlanSolutionPtr last_plan_solution_;
228
+ planning_interface::MotionPlanResponse last_plan_solution_;
189
229
190
230
// common properties for goals
191
231
// TODO(henningkayser): support goal tolerances
0 commit comments