moveit2
The MoveIt Motion Planning Framework for ROS 2.
always_insert_never_prune_policy.cpp
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 
24 #include <memory>
25 #include <sstream>
26 #include <string>
27 
28 #include <warehouse_ros/message_collection.h>
30 
31 #include <moveit_msgs/msg/motion_plan_request.hpp>
32 #include <moveit_msgs/msg/robot_trajectory.hpp>
33 #include <moveit_msgs/srv/get_cartesian_path.hpp>
34 
40 
41 namespace moveit_ros
42 {
43 namespace trajectory_cache
44 {
45 
46 using ::warehouse_ros::MessageCollection;
47 using ::warehouse_ros::MessageWithMetadata;
48 using ::warehouse_ros::Metadata;
49 using ::warehouse_ros::Query;
50 
51 using ::moveit::core::MoveItErrorCode;
52 using ::moveit::planning_interface::MoveGroupInterface;
53 
55 using ::moveit_msgs::msg::RobotTrajectory;
56 using ::moveit_msgs::srv::GetCartesianPath;
57 
58 using ::moveit_ros::trajectory_cache::FeaturesInterface;
59 
60 namespace
61 {
62 
63 const std::string EXECUTION_TIME = "execution_time_s";
64 const std::string FRACTION = "fraction";
65 const std::string PLANNING_TIME = "planning_time_s";
66 
67 } // namespace
68 
69 // =================================================================================================
70 // AlwaysInsertNeverPrunePolicy.
71 // =================================================================================================
72 // moveit_msgs::msg::MotionPlanRequest <=> moveit::planning_interface::MoveGroupInterface::Plan
73 
74 AlwaysInsertNeverPrunePolicy::AlwaysInsertNeverPrunePolicy() : name_("AlwaysInsertNeverPrunePolicy")
75 {
76  exact_matching_supported_features_ = AlwaysInsertNeverPrunePolicy::getSupportedFeatures(/*start_tolerance=*/0.0,
77  /*goal_tolerance=*/0.0);
78 }
79 
80 std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>>
81 AlwaysInsertNeverPrunePolicy::getSupportedFeatures(double start_tolerance, double goal_tolerance)
82 {
83  std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>> out;
84  out.reserve(6);
85 
86  // Start.
87  out.push_back(std::make_unique<WorkspaceFeatures>());
88  out.push_back(std::make_unique<StartStateJointStateFeatures>(start_tolerance));
89 
90  // Goal.
91  out.push_back(std::make_unique<MaxSpeedAndAccelerationFeatures>());
92  out.push_back(std::make_unique<GoalConstraintsFeatures>(goal_tolerance));
93  out.push_back(std::make_unique<PathConstraintsFeatures>(goal_tolerance));
94  out.push_back(std::make_unique<TrajectoryConstraintsFeatures>(goal_tolerance));
95 
96  return out;
97 }
98 
100 {
101  return name_;
102 }
103 
104 MoveItErrorCode AlwaysInsertNeverPrunePolicy::checkCacheInsertInputs(const MoveGroupInterface& move_group,
105  const MessageCollection<RobotTrajectory>& /*coll*/,
106  const MotionPlanRequest& key,
107  const MoveGroupInterface::Plan& value)
108 {
109  std::string frame_id = getWorkspaceFrameId(move_group, key.workspace_parameters);
110 
111  // Check key.
112  if (frame_id.empty())
113  {
114  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
115  name_ + ": Skipping insert: Workspace frame ID cannot be empty.");
116  }
117  if (key.goal_constraints.empty())
118  {
119  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN, name_ + ": Skipping insert: No goal.");
120  }
121 
122  // Check value.
123  if (value.trajectory.joint_trajectory.points.empty())
124  {
125  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN, name_ + ": Empty joint trajectory points.");
126  }
127  if (value.trajectory.joint_trajectory.joint_names.empty())
128  {
129  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
130  name_ + ": Skipping insert: Empty joint trajectory joint names.");
131  }
132  if (!value.trajectory.multi_dof_joint_trajectory.points.empty())
133  {
134  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
135  name_ + ": Skipping insert: Multi-DOF trajectory plans are not supported.");
136  }
137  if (value.trajectory.joint_trajectory.header.frame_id.empty())
138  {
139  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
140  name_ + ": Skipping insert: Trajectory frame ID cannot be empty.");
141  }
142  if (frame_id != value.trajectory.joint_trajectory.header.frame_id)
143  {
144  std::stringstream ss;
145  ss << "Skipping insert: Plan request frame `" << frame_id << "` does not match plan frame `"
146  << value.trajectory.joint_trajectory.header.frame_id << "`.";
147  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN, ss.str());
148  }
149 
150  return MoveItErrorCode::SUCCESS;
151 }
152 
153 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> AlwaysInsertNeverPrunePolicy::fetchMatchingEntries(
154  const MoveGroupInterface& move_group, const MessageCollection<RobotTrajectory>& coll, const MotionPlanRequest& key,
155  const MoveGroupInterface::Plan& /*value*/, double exact_match_precision)
156 {
157  Query::Ptr query = coll.createQuery();
158  for (const auto& feature : exact_matching_supported_features_)
159  {
160  if (MoveItErrorCode ret = feature->appendFeaturesAsExactFetchQuery(*query, key, move_group, exact_match_precision);
161  !ret)
162  {
163  return {};
164  }
165  }
166  return coll.queryList(query, /*metadata_only=*/true);
167 }
168 
170  const MoveGroupInterface& /*move_group*/, const MotionPlanRequest& /*key*/,
171  const MoveGroupInterface::Plan& /*value*/, const MessageWithMetadata<RobotTrajectory>::ConstPtr& /*matching_entry*/,
172  std::string* reason)
173 {
174  if (reason != nullptr)
175  {
176  *reason = "Never prune.";
177  }
178  return false; // Never prune.
179 }
180 
181 bool AlwaysInsertNeverPrunePolicy::shouldInsert(const MoveGroupInterface& /*move_group*/,
182  const MotionPlanRequest& /*key*/,
183  const MoveGroupInterface::Plan& /*value*/, std::string* reason)
184 {
185  if (reason != nullptr)
186  {
187  *reason = "Always insert.";
188  }
189  return true; // Always insert.
190 }
191 
192 MoveItErrorCode AlwaysInsertNeverPrunePolicy::appendInsertMetadata(Metadata& metadata,
193  const MoveGroupInterface& move_group,
194  const MotionPlanRequest& key,
195  const MoveGroupInterface::Plan& value)
196 {
197  for (const auto& feature : exact_matching_supported_features_)
198  {
199  if (MoveItErrorCode ret = feature->appendFeaturesAsInsertMetadata(metadata, key, move_group); !ret)
200  {
201  return ret;
202  }
203  }
204 
205  // Append ValueT metadata.
206  metadata.append(EXECUTION_TIME, getExecutionTime(value.trajectory));
207  metadata.append(PLANNING_TIME, value.planning_time);
208 
209  return MoveItErrorCode::SUCCESS;
210 }
211 
213 {
214  return;
215 }
216 
217 // =================================================================================================
218 // CartesianAlwaysInsertNeverPrunePolicy.
219 // =================================================================================================
220 // moveit_msgs::srv::GetCartesianPath::Request <=> moveit_msgs::srv::GetCartesianPath::Response
221 
223  : name_("CartesianAlwaysInsertNeverPrunePolicy")
224 {
225  exact_matching_supported_features_ =
227  /*goal_tolerance=*/0.0, /*min_fraction=*/0.0);
228 }
229 
230 std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>>
231 CartesianAlwaysInsertNeverPrunePolicy::getSupportedFeatures(double start_tolerance, double goal_tolerance,
232  double min_fraction)
233 {
234  std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>> out;
235  out.reserve(7);
236 
237  // Start.
238  out.push_back(std::make_unique<CartesianWorkspaceFeatures>());
239  out.push_back(std::make_unique<CartesianStartStateJointStateFeatures>(start_tolerance));
240 
241  // Goal.
242  out.push_back(std::make_unique<CartesianMaxSpeedAndAccelerationFeatures>());
243  out.push_back(std::make_unique<CartesianMaxStepAndJumpThresholdFeatures>());
244  out.push_back(std::make_unique<CartesianWaypointsFeatures>(goal_tolerance));
245  out.push_back(std::make_unique<CartesianPathConstraintsFeatures>(goal_tolerance));
246 
247  // Min fraction.
248  out.push_back(std::make_unique<QueryOnlyGTEFeature<double, GetCartesianPath::Request>>(FRACTION, min_fraction));
249 
250  return out;
251 }
252 
254 {
255  return name_;
256 }
257 
259  const MoveGroupInterface& move_group, const MessageCollection<RobotTrajectory>& /*coll*/,
260  const GetCartesianPath::Request& key, const GetCartesianPath::Response& value)
261 {
262  std::string frame_id = getCartesianPathRequestFrameId(move_group, key);
263 
264  // Check key.
265  if (frame_id.empty())
266  {
267  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
268  name_ + ": Skipping insert: Workspace frame ID cannot be empty.");
269  }
270  if (key.waypoints.empty())
271  {
272  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN, name_ + ": Skipping insert: No waypoints.");
273  }
274 
275  // Check value.
276  if (value.solution.joint_trajectory.points.empty())
277  {
278  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN, name_ + ": Empty joint trajectory points.");
279  }
280  if (value.solution.joint_trajectory.joint_names.empty())
281  {
282  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
283  name_ + ": Skipping insert: Empty joint trajectory joint names.");
284  }
285  if (!value.solution.multi_dof_joint_trajectory.points.empty())
286  {
287  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
288  name_ + ": Skipping insert: Multi-DOF trajectory plans are not supported.");
289  }
290  if (value.solution.joint_trajectory.header.frame_id.empty())
291  {
292  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN,
293  name_ + ": Skipping insert: Trajectory frame ID cannot be empty.");
294  }
295  if (frame_id != value.solution.joint_trajectory.header.frame_id)
296  {
297  std::stringstream ss;
298  ss << "Skipping insert: Plan request frame `" << frame_id << "` does not match plan frame `"
299  << value.solution.joint_trajectory.header.frame_id << "`.";
300  return MoveItErrorCode(MoveItErrorCode::INVALID_MOTION_PLAN, ss.str());
301  }
302 
303  return MoveItErrorCode::SUCCESS;
304 }
305 
306 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> CartesianAlwaysInsertNeverPrunePolicy::fetchMatchingEntries(
307  const MoveGroupInterface& move_group, const MessageCollection<RobotTrajectory>& coll,
308  const GetCartesianPath::Request& key, const GetCartesianPath::Response& /*value*/, double exact_match_precision)
309 {
310  Query::Ptr query = coll.createQuery();
311  for (const auto& feature : exact_matching_supported_features_)
312  {
313  if (MoveItErrorCode ret = feature->appendFeaturesAsExactFetchQuery(*query, key, move_group, exact_match_precision);
314  !ret)
315  {
316  return {};
317  }
318  }
319  return coll.queryList(query, /*metadata_only=*/true);
320 }
321 
323  const MoveGroupInterface& /*move_group*/, const GetCartesianPath::Request& /*key*/,
324  const GetCartesianPath::Response& /*value*/,
325  const MessageWithMetadata<RobotTrajectory>::ConstPtr& /*matching_entry*/, std::string* reason)
326 {
327  if (reason != nullptr)
328  {
329  *reason = "Never prune.";
330  }
331  return false; // Never prune.
332 }
333 
334 bool CartesianAlwaysInsertNeverPrunePolicy::shouldInsert(const MoveGroupInterface& /*move_group*/,
335  const GetCartesianPath::Request& /*key*/,
336  const GetCartesianPath::Response& /*value*/,
337  std::string* reason)
338 {
339  if (reason != nullptr)
340  {
341  *reason = "Always insert.";
342  }
343  return true; // Always insert.
344 }
345 
347  const MoveGroupInterface& move_group,
348  const GetCartesianPath::Request& key,
349  const GetCartesianPath::Response& value)
350 {
351  for (const auto& feature : exact_matching_supported_features_)
352  {
353  if (MoveItErrorCode ret = feature->appendFeaturesAsInsertMetadata(metadata, key, move_group); !ret)
354  {
355  return ret;
356  }
357  }
358 
359  // Append ValueT metadata.
360  metadata.append(EXECUTION_TIME, getExecutionTime(value.solution));
361  metadata.append(FRACTION, value.fraction);
362 
363  return MoveItErrorCode::SUCCESS;
364 }
365 
367 {
368  return;
369 }
370 
371 } // namespace trajectory_cache
372 } // namespace moveit_ros
A cache insertion policy that always decides to insert and never decides to prune.
std::vector< warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr > fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value, double exact_match_precision) override
Fetches all "matching" cache entries for comparison for pruning.
moveit::core::MoveItErrorCode checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value) override
Checks inputs to the cache insert call to see if we should abort instead.
bool shouldPruneMatchingEntry(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value, const warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr &matching_entry, std::string *reason=nullptr) override
bool shouldInsert(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value, std::string *reason=nullptr) override
Returns whether the insertion candidate should be inserted into the cache.
static std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::msg::MotionPlanRequest > > > getSupportedFeatures(double start_tolerance, double goal_tolerance)
Configures and returns a vector of feature extractors that can be used with this policy.
std::string getName() const override
Gets the name of the cache insert policy.
moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata &metadata, const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value) override
Appends the insert metadata with the features supported by the policy.
std::string getName() const override
Gets the name of the cache insert policy.
static std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request > > > getSupportedFeatures(double start_tolerance, double goal_tolerance, double min_fraction)
Configures and returns a vector of feature extractors that can be used with this policy.
bool shouldInsert(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, std::string *reason=nullptr) override
Returns whether the insertion candidate should be inserted into the cache.
moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata &metadata, const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value) override
Appends the insert metadata with the features supported by the policy.
std::vector< warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr > fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, double exact_match_precision) override
Fetches all "matching" cache entries for comparison for pruning.
bool shouldPruneMatchingEntry(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, const warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr &matching_entry, std::string *reason=nullptr) override
moveit::core::MoveItErrorCode checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value) override
Checks inputs to the cache insert call to see if we should abort instead.
User-specified constant features to key the trajectory cache on.
moveit_msgs::srv::GetCartesianPath::Request features to key the trajectory cache on.
moveit_msgs::msg::MotionPlanRequest features to key the trajectory cache on.
Utilities used by the trajectory_cache package.
std::string getWorkspaceFrameId(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::WorkspaceParameters &workspace_parameters)
Gets workspace frame ID. If workspace_parameters has no frame ID, fetch it from move_group.
double getExecutionTime(const moveit_msgs::msg::RobotTrajectory &trajectory)
Returns the execution time of the trajectory in double seconds.
Definition: utils.cpp:146
std::string getCartesianPathRequestFrameId(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &path_request)
Gets cartesian path request frame ID. If path_request has no frame ID, fetch it from move_group.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest