moveit2
The MoveIt Motion Planning Framework for ROS 2.
motion_plan_request_features.hpp
Go to the documentation of this file.
1 // Copyright 2024 Intrinsic Innovation LLC.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
22 #pragma once
23 
24 #include <warehouse_ros/message_collection.h>
26 #include <moveit_msgs/msg/robot_trajectory.hpp>
27 #include <moveit_msgs/msg/motion_plan_request.hpp>
28 
30 
31 namespace moveit_ros
32 {
33 namespace trajectory_cache
34 {
35 
36 // "Start" features. ===============================================================================
37 
55 class WorkspaceFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
56 {
57 public:
59 
60  std::string getName() const override;
61 
63  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
65  double exact_match_precision) const override;
66 
68  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
70  double exact_match_precision) const override;
71 
73  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
75 
76 private:
77  const std::string name_;
78 };
79 
91 class StartStateJointStateFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
92 {
93 public:
94  StartStateJointStateFeatures(double match_tolerance);
95 
96  std::string getName() const override;
97 
99  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
101  double exact_match_precision) const override;
102 
104  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
106  double exact_match_precision) const override;
107 
109  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
111 
112 private:
113  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
114  warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
115  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
116 
117  const std::string name_;
118  const double match_tolerance_;
119 };
120 
121 // "Goal" features. ================================================================================
122 
132 class MaxSpeedAndAccelerationFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
133 {
134 public:
136 
137  std::string getName() const override;
138 
140  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
142  double exact_match_precision) const override;
143 
145  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
147  double exact_match_precision) const override;
148 
150  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
152 
153 private:
154  const std::string name_;
155 };
156 
163 class GoalConstraintsFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
164 {
165 public:
166  GoalConstraintsFeatures(double match_tolerance);
167 
168  std::string getName() const override;
169 
171  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
173  double exact_match_precision) const override;
174 
176  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
178  double exact_match_precision) const override;
179 
181  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
183 
184 private:
185  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
186  warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
187  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
188 
189  const std::string name_;
190  const double match_tolerance_;
191 };
192 
199 class PathConstraintsFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
200 {
201 public:
202  PathConstraintsFeatures(double match_tolerance);
203 
204  std::string getName() const override;
205 
207  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
209  double exact_match_precision) const override;
210 
212  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
214  double exact_match_precision) const override;
215 
217  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
219 
220 private:
221  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
222  warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
223  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
224 
225  const std::string name_;
226  const double match_tolerance_;
227 };
228 
235 class TrajectoryConstraintsFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
236 {
237 public:
238  TrajectoryConstraintsFeatures(double match_tolerance);
239 
240  std::string getName() const override;
241 
243  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
245  double exact_match_precision) const override;
246 
248  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
250  double exact_match_precision) const override;
251 
253  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
255 
256 private:
257  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
258  warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
259  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
260 
261  const std::string name_;
262  const double match_tolerance_;
263 };
264 
265 } // namespace trajectory_cache
266 } // namespace moveit_ros
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Client class to conveniently use the ROS interfaces provided by the move_group node.
Extracts features from the goal_constraints field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
std::string getName() const override
Gets the name of the features implementation.
Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request.
std::string getName() const override
Gets the name of the features implementation.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
Extracts features from the path_constraints field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
std::string getName() const override
Gets the name of the features implementation.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
Extracts details of the joint state from the start_state field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
std::string getName() const override
Gets the name of the features implementation.
Extracts features from the trajectory_constraints field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
std::string getName() const override
Gets the name of the features implementation.
Extracts group name and details of the workspace_parameters field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
std::string getName() const override
Gets the name of the features implementation.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
Abstract template class for extracting features from some FeatureSourceT.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest