moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_always_insert_never_prune_policy_with_move_group.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
19#include <memory>
20#include <utility>
21
22#include <gtest/gtest.h>
23#include <warehouse_ros/message_collection.h>
24
26#include <moveit_msgs/msg/motion_plan_request.hpp>
27#include <moveit_msgs/msg/robot_trajectory.hpp>
28#include <moveit_msgs/srv/get_cartesian_path.hpp>
29
33
34#include "../fixtures/move_group_fixture.hpp"
35
36namespace
37{
38
39using ::warehouse_ros::MessageCollection;
40using ::warehouse_ros::MessageWithMetadata;
41using ::warehouse_ros::Metadata;
42using ::warehouse_ros::Query;
43
44using ::moveit::core::MoveItErrorCode;
45using ::moveit::planning_interface::MoveGroupInterface;
46
47using ::moveit_msgs::msg::MotionPlanRequest;
48using ::moveit_msgs::msg::RobotTrajectory;
49using ::moveit_msgs::srv::GetCartesianPath;
50
51using ::moveit_ros::trajectory_cache::AlwaysInsertNeverPrunePolicy;
52using ::moveit_ros::trajectory_cache::CartesianAlwaysInsertNeverPrunePolicy;
53using ::moveit_ros::trajectory_cache::constructGetCartesianPathRequest;
54using ::moveit_ros::trajectory_cache::FeaturesInterface;
55
56// =================================================================================================
57// AlwaysInsertNeverPrunePolicy.
58// =================================================================================================
59
60TEST_F(MoveGroupFixture, AlwaysInsertNeverPrunePolicyChecks)
61{
62 // Setup.
63 AlwaysInsertNeverPrunePolicy policy;
64
65 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>("test_db", policy.getName());
66
67 MotionPlanRequest valid_msg;
68 MoveGroupInterface::Plan valid_plan;
69
70 // Valid case, as control.
71 {
72 valid_msg.workspace_parameters.header.frame_id = "panda_link0";
73 valid_msg.goal_constraints.emplace_back();
74
75 valid_plan.trajectory.joint_trajectory.header.frame_id = "panda_link0";
76 valid_plan.trajectory.joint_trajectory.joint_names.emplace_back();
77 valid_plan.trajectory.joint_trajectory.points.emplace_back();
78
79 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, valid_plan);
80 ASSERT_TRUE(ret) << ret.message;
81 }
82
83 // We can't test workspace ID frame empty.
84 // But it technically should be unreachable as long as the robot description is correct.
85
86 // No goal.
87 {
88 MotionPlanRequest msg = valid_msg;
89 msg.goal_constraints.clear();
90 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, msg, valid_plan));
91 }
92
93 // Empty joint trajectory points.
94 {
95 MoveGroupInterface::Plan plan = valid_plan;
96 plan.trajectory.joint_trajectory.points.clear();
97 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
98 }
99
100 // Empty joint trajectory names.
101 {
102 MoveGroupInterface::Plan plan = valid_plan;
103 plan.trajectory.joint_trajectory.joint_names.clear();
104 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
105 }
106
107 // Multi-DOF trajectory plan.
108 {
109 MoveGroupInterface::Plan plan = valid_plan;
110 plan.trajectory.multi_dof_joint_trajectory.points.emplace_back();
111 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
112 }
113
114 // Trajectory frame ID empty.
115 {
116 MoveGroupInterface::Plan plan = valid_plan;
117 plan.trajectory.joint_trajectory.header.frame_id = "";
118 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
119 }
120
121 // Mismatched frames.
122 {
123 MotionPlanRequest msg = valid_msg;
124 MoveGroupInterface::Plan plan = valid_plan;
125 msg.workspace_parameters.header.frame_id = "panda_link0";
126 plan.trajectory.joint_trajectory.header.frame_id = "clearly_a_different_frame";
127 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, msg, plan));
128 }
129}
130
131TEST_F(MoveGroupFixture, AlwaysInsertNeverPrunePolicyWorks)
132{
133 AlwaysInsertNeverPrunePolicy policy;
134
135 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>("test_db", policy.getName());
136 ASSERT_EQ(coll.count(), 0);
137
138 // Setup. Get valid entries to insert.
140 MoveGroupInterface::Plan plan;
141 MoveItErrorCode ret = MoveItErrorCode::FAILURE;
142
143 MotionPlanRequest another_msg;
144 MoveGroupInterface::Plan another_plan;
145 MoveItErrorCode another_ret = MoveItErrorCode::FAILURE;
146
147 do
148 {
149 ASSERT_TRUE(move_group_->setPoseTarget(move_group_->getRandomPose()));
150 move_group_->constructMotionPlanRequest(msg);
151 ret = move_group_->plan(plan);
152 } while (!ret || plan.trajectory.joint_trajectory.points.empty()); // Sometimes the plan fails with the random pose.
153
154 do
155 {
156 ASSERT_TRUE(move_group_->setPoseTarget(move_group_->getRandomPose()));
157 move_group_->constructMotionPlanRequest(another_msg);
158 another_ret = move_group_->plan(another_plan);
159 } while (another_msg == msg || !another_ret ||
160 another_plan.trajectory.joint_trajectory.points
161 .empty()); // Also, sometimes the random pose happens to be the same.
162
163 // Ensure that the entries are valid.
164 {
165 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, msg, plan);
166 ASSERT_TRUE(ret) << ret.message;
167 }
168 {
169 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, another_msg, another_plan);
170 ASSERT_TRUE(ret) << ret.message;
171 }
172
173 // Core test. ====================================================================================
174 // NOTE: Be mindful that the policy is stateful.
175
176 // Insert messages and check if policy-specific additional metadata are added.
177 size_t count = 0;
178 for (const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
179 {
180 Metadata::Ptr metadata = coll.createMetadata();
181 EXPECT_TRUE(policy.appendInsertMetadata(*metadata, *move_group_, msg_plan_pair.first, msg_plan_pair.second));
182 EXPECT_TRUE(metadata->lookupField("execution_time_s"));
183 EXPECT_TRUE(metadata->lookupField("planning_time_s"));
184
185 // We add two to test the prune predicate, as appropriate.
186 coll.insert(msg_plan_pair.second.trajectory, metadata);
187 coll.insert(msg_plan_pair.second.trajectory, metadata);
188 count += 2;
189 ASSERT_EQ(coll.count(), count);
190 }
191
192 // Fetch with features from getSupportedFeatures and fetchMatchingEntries.
193 // In this case the results should also match with fetchMatchingEntries.
194 //
195 // We also test the predicates here.
196 std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>> features =
197 AlwaysInsertNeverPrunePolicy::getSupportedFeatures(/*start_tolerance=*/0.025, /*goal_tolerance=*/0.001);
198
199 for (const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
200 {
201 Query::Ptr query = coll.createQuery();
202 for (const auto& feature : features)
203 {
204 ASSERT_TRUE(feature->appendFeaturesAsExactFetchQuery(*query, msg_plan_pair.first, *move_group_,
205 /*exact_match_precision=*/0.0001));
206 }
207
208 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> feature_fetch =
209 coll.queryList(query, /*metadata_only=*/true);
210 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> policy_fetch = policy.fetchMatchingEntries(
211 *move_group_, coll, msg_plan_pair.first, msg_plan_pair.second, /*exact_match_precision=*/0.0001);
212
213 ASSERT_EQ(feature_fetch.size(), 2);
214 ASSERT_EQ(policy_fetch.size(), 2);
215 for (size_t i = 0; i < feature_fetch.size(); ++i)
216 {
217 ASSERT_EQ(*feature_fetch[i], *policy_fetch[i]);
218
219 // Policy is never prune.
220 std::string prune_reason;
221 EXPECT_FALSE(policy.shouldPruneMatchingEntry(*move_group_, msg_plan_pair.first, msg_plan_pair.second,
222 policy_fetch[i], &prune_reason));
223 EXPECT_FALSE(prune_reason.empty());
224 }
225
226 // Policy is always insert.
227 std::string insert_reason;
228 EXPECT_TRUE(policy.shouldInsert(*move_group_, msg_plan_pair.first, msg_plan_pair.second, &insert_reason));
229 EXPECT_FALSE(insert_reason.empty());
230
231 policy.reset();
232 }
233}
234
235// =================================================================================================
236// CartesianAlwaysInsertNeverPrunePolicy.
237// =================================================================================================
238
239TEST_F(MoveGroupFixture, CartesianAlwaysInsertNeverPrunePolicyChecks)
240{
241 // Setup.
242 CartesianAlwaysInsertNeverPrunePolicy policy;
243
244 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>("test_db", policy.getName());
245
246 GetCartesianPath::Request valid_msg;
247 GetCartesianPath::Response valid_plan;
248 valid_plan.fraction = -1;
249
250 do
251 {
252 std::vector<geometry_msgs::msg::Pose> waypoints;
253 waypoints.push_back(move_group_->getCurrentPose().pose);
254 waypoints.push_back(move_group_->getRandomPose().pose);
255
256 valid_msg = constructGetCartesianPathRequest(*move_group_, waypoints, /*max_step=*/0.01, /*jump_threshold=*/0.0);
257// TODO: Swap this over to the new computeCartesianPath API.
258#pragma GCC diagnostic push
259#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
260 valid_plan.fraction = move_group_->computeCartesianPath(valid_msg.waypoints, valid_msg.max_step,
261 valid_msg.jump_threshold, valid_plan.solution);
262#pragma GCC diagnostic pop
263 } while (valid_plan.fraction <= 0); // Sometimes the plan fails with the random pose.
264
265 // Valid case, as control.
266 {
267 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, valid_plan);
268 ASSERT_TRUE(ret) << ret.message;
269 }
270
271 // We can't test workspace ID frame empty.
272 // But it technically should be unreachable as long as the robot description is correct.
273
274 // No waypoints.
275 {
276 GetCartesianPath::Request msg = valid_msg;
277 msg.waypoints.clear();
278 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, msg, valid_plan));
279 }
280
281 // Empty joint trajectory points.
282 {
283 GetCartesianPath::Response plan = valid_plan;
284 plan.solution.joint_trajectory.points.clear();
285 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
286 }
287
288 // Empty joint trajectory names.
289 {
290 GetCartesianPath::Response plan = valid_plan;
291 plan.solution.joint_trajectory.joint_names.clear();
292 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
293 }
294
295 // Multi-DOF trajectory plan.
296 {
297 GetCartesianPath::Response plan = valid_plan;
298 plan.solution.multi_dof_joint_trajectory.points.emplace_back();
299 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
300 }
301
302 // Trajectory frame ID empty.
303 {
304 GetCartesianPath::Response plan = valid_plan;
305 plan.solution.joint_trajectory.header.frame_id = "";
306 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
307 }
308
309 // Mismatched frames.
310 {
311 GetCartesianPath::Request msg = valid_msg;
312 GetCartesianPath::Response plan = valid_plan;
313 msg.header.frame_id = "panda_link0";
314 plan.solution.joint_trajectory.header.frame_id = "clearly_a_different_frame";
315 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, msg, plan));
316 }
317}
318
319TEST_F(MoveGroupFixture, CartesianAlwaysInsertNeverPrunePolicyWorks)
320{
321 CartesianAlwaysInsertNeverPrunePolicy policy;
322
323 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>("test_db", policy.getName());
324 ASSERT_EQ(coll.count(), 0);
325
326 // Setup. Get valid entries to insert.
327 GetCartesianPath::Request msg;
328 GetCartesianPath::Response plan;
329 plan.fraction = -1;
330
331 GetCartesianPath::Request another_msg;
332 GetCartesianPath::Response another_plan;
333 another_plan.fraction = -1;
334
335 do
336 {
337 std::vector<geometry_msgs::msg::Pose> waypoints;
338 waypoints.push_back(move_group_->getCurrentPose().pose);
339 waypoints.push_back(move_group_->getRandomPose().pose);
340
341 msg = constructGetCartesianPathRequest(*move_group_, waypoints, /*max_step=*/0.01, /*jump_threshold=*/0.0);
342// TODO: Swap this over to the new computeCartesianPath API.
343#pragma GCC diagnostic push
344#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
345 plan.fraction = move_group_->computeCartesianPath(msg.waypoints, msg.max_step, msg.jump_threshold, plan.solution);
346#pragma GCC diagnostic pop
347 } while (plan.fraction <= -1 &&
348 plan.solution.joint_trajectory.points.size() < 2); // Sometimes the plan fails with the random pose.
349
350 do
351 {
352 std::vector<geometry_msgs::msg::Pose> waypoints;
353 waypoints.push_back(move_group_->getCurrentPose().pose);
354 waypoints.push_back(move_group_->getRandomPose().pose);
355
356 another_msg = constructGetCartesianPathRequest(*move_group_, waypoints, /*max_step=*/0.01, /*jump_threshold=*/0.0);
357// TODO: Swap this over to the new computeCartesianPath API.
358#pragma GCC diagnostic push
359#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
360 another_plan.fraction = move_group_->computeCartesianPath(another_msg.waypoints, another_msg.max_step,
361 another_msg.jump_threshold, another_plan.solution);
362#pragma GCC diagnostic pop
363 } while (another_plan.fraction <= -1 &&
364 plan.solution.joint_trajectory.points.size() < 2); // Sometimes the plan fails with the random pose.
365
366 // Ensure that the entries are valid.
367 {
368 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, msg, plan);
369 ASSERT_TRUE(ret) << ret.message;
370 }
371 {
372 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, another_msg, another_plan);
373 ASSERT_TRUE(ret) << ret.message;
374 }
375
376 // Core test. ====================================================================================
377 // NOTE: Be mindful that the policy is stateful.
378
379 // Insert messages and check if policy-specific additional metadata are added.
380 size_t count = 0;
381 for (const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
382 {
383 Metadata::Ptr metadata = coll.createMetadata();
384 EXPECT_TRUE(policy.appendInsertMetadata(*metadata, *move_group_, msg_plan_pair.first, msg_plan_pair.second));
385 EXPECT_TRUE(metadata->lookupField("execution_time_s"));
386 EXPECT_TRUE(metadata->lookupField("fraction"));
387
388 // We add two to test the prune predicate, as appropriate.
389 coll.insert(msg_plan_pair.second.solution, metadata);
390 coll.insert(msg_plan_pair.second.solution, metadata);
391 count += 2;
392 ASSERT_EQ(coll.count(), count);
393 }
394
395 // Fetch with features from getSupportedFeatures and fetchMatchingEntries.
396 // In this case the results should also match with fetchMatchingEntries.
397 //
398 // We also test the predicates here.
399 std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>> features =
400 CartesianAlwaysInsertNeverPrunePolicy::getSupportedFeatures(/*start_tolerance=*/0.025,
401 /*goal_tolerance=*/0.001,
402 /*min_fraction=*/0.0);
403
404 for (const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
405 {
406 Query::Ptr query = coll.createQuery();
407 for (const auto& feature : features)
408 {
409 ASSERT_TRUE(feature->appendFeaturesAsExactFetchQuery(*query, msg_plan_pair.first, *move_group_,
410 /*exact_match_precision=*/0.0001));
411 }
412
413 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> feature_fetch =
414 coll.queryList(query, /*metadata_only=*/true);
415 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> policy_fetch = policy.fetchMatchingEntries(
416 *move_group_, coll, msg_plan_pair.first, msg_plan_pair.second, /*exact_match_precision=*/0.0001);
417
418 ASSERT_EQ(feature_fetch.size(), 2);
419 ASSERT_EQ(policy_fetch.size(), 2);
420 for (size_t i = 0; i < feature_fetch.size(); ++i)
421 {
422 ASSERT_EQ(*feature_fetch[i], *policy_fetch[i]);
423
424 // Policy is never prune.
425 std::string prune_reason;
426 EXPECT_FALSE(policy.shouldPruneMatchingEntry(*move_group_, msg_plan_pair.first, msg_plan_pair.second,
427 policy_fetch[i], &prune_reason));
428 EXPECT_FALSE(prune_reason.empty());
429 }
430
431 // Policy is always insert.
432 std::string insert_reason;
433 EXPECT_TRUE(policy.shouldInsert(*move_group_, msg_plan_pair.first, msg_plan_pair.second, &insert_reason));
434 EXPECT_FALSE(insert_reason.empty());
435
436 policy.reset();
437 }
438}
439
440} // namespace
441
442int main(int argc, char** argv)
443{
444 rclcpp::init(argc, argv);
445 ::testing::InitGoogleTest(&argc, argv);
446 int result = RUN_ALL_TESTS();
447 rclcpp::shutdown();
448 return result;
449}
A cache insertion policy that always decides to insert and never decides to prune.
Test fixture to spin up a node to start a move group with.
Abstract template class for extracting features from some FeatureSourceT.
Utilities used by the trajectory_cache package.
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
moveit_msgs::srv::GetCartesianPath::Request constructGetCartesianPathRequest(moveit::planning_interface::MoveGroupInterface &move_group, const std::vector< geometry_msgs::msg::Pose > &waypoints, double max_step, double jump_threshold, bool avoid_collisions=true)
Constructs a GetCartesianPath request.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
robot_trajectory::RobotTrajectoryPtr trajectory
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.