moveit2
The MoveIt Motion Planning Framework for ROS 2.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Pages
get_cartesian_path_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/srv/get_cartesian_path.hpp>
27 
29 
30 namespace moveit_ros
31 {
32 namespace trajectory_cache
33 {
34 
35 // "Start" features. ===============================================================================
36 
40 class CartesianWorkspaceFeatures final : public FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>
41 {
42 public:
44 
45  std::string getName() const override;
46 
48  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
49  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
50 
52  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
53  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
54 
56  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata,
57  const moveit_msgs::srv::GetCartesianPath::Request& source,
59 
60 private:
61  const std::string name_;
62 };
63 
73  : public FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>
74 {
75 public:
76  CartesianStartStateJointStateFeatures(double match_tolerance);
77 
78  std::string getName() const override;
79 
81  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
82  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
83 
85  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
86  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
87 
89  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata,
90  const moveit_msgs::srv::GetCartesianPath::Request& source,
92 
93 private:
94  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
95  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
96  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
97 
98  const std::string name_;
99  const double match_tolerance_;
100 };
101 
102 // "Goal" features. ================================================================================
103 
114  : public FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>
115 {
116 public:
118 
119  std::string getName() const override;
120 
122  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
123  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
124 
126  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
127  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
128 
130  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata,
131  const moveit_msgs::srv::GetCartesianPath::Request& source,
133 
134 private:
135  const std::string name_;
136 };
137 
147  : public FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>
148 {
149 public:
151 
152  std::string getName() const override;
153 
155  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
156  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
157 
159  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
160  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
161 
163  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata,
164  const moveit_msgs::srv::GetCartesianPath::Request& source,
166 
167 private:
168  const std::string name_;
169 };
170 
183 class CartesianWaypointsFeatures final : public FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>
184 {
185 public:
186  CartesianWaypointsFeatures(double match_tolerance);
187 
188  std::string getName() const override;
189 
191  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
192  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
193 
195  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
196  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
197 
199  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata,
200  const moveit_msgs::srv::GetCartesianPath::Request& source,
202 
203 private:
204  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
205  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
206  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
207 
208  const std::string name_;
209  const double match_tolerance_;
210 };
211 
218 class CartesianPathConstraintsFeatures final : public FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>
219 {
220 public:
221  CartesianPathConstraintsFeatures(double match_tolerance);
222 
223  std::string getName() const override;
224 
226  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
227  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
228 
230  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
231  const moveit::planning_interface::MoveGroupInterface& move_group, double exact_match_precision) const override;
232 
234  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata,
235  const moveit_msgs::srv::GetCartesianPath::Request& source,
237 
238 private:
239  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
240  warehouse_ros::Query& query, const moveit_msgs::srv::GetCartesianPath::Request& source,
241  const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;
242 
243  const std::string name_;
244  const double match_tolerance_;
245 };
246 
247 } // namespace trajectory_cache
248 } // 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 max velocity and acceleration scaling, and cartesian speed limits from the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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 appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
Extracts features from the path_constraints field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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 appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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 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::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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 waypoints and link_name field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
Extracts group name and frame ID from the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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::srv::GetCartesianPath::Request &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.
Abstract template class for extracting features from some FeatureSourceT.