22#include <gtest/gtest.h>
23#include <warehouse_ros/message_collection.h>
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>
34#include "../fixtures/move_group_fixture.hpp"
39using ::warehouse_ros::MessageCollection;
40using ::warehouse_ros::MessageWithMetadata;
41using ::warehouse_ros::Metadata;
42using ::warehouse_ros::Query;
44using ::moveit::core::MoveItErrorCode;
45using ::moveit::planning_interface::MoveGroupInterface;
47using ::moveit_msgs::msg::MotionPlanRequest;
48using ::moveit_msgs::msg::RobotTrajectory;
49using ::moveit_msgs::srv::GetCartesianPath;
51using ::moveit_ros::trajectory_cache::AlwaysInsertNeverPrunePolicy;
52using ::moveit_ros::trajectory_cache::CartesianAlwaysInsertNeverPrunePolicy;
53using ::moveit_ros::trajectory_cache::constructGetCartesianPathRequest;
54using ::moveit_ros::trajectory_cache::FeaturesInterface;
63 AlwaysInsertNeverPrunePolicy policy;
65 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>(
"test_db", policy.getName());
68 MoveGroupInterface::Plan valid_plan;
72 valid_msg.workspace_parameters.header.frame_id =
"panda_link0";
73 valid_msg.goal_constraints.emplace_back();
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();
79 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, valid_plan);
80 ASSERT_TRUE(ret) << ret.message;
89 msg.goal_constraints.clear();
90 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, msg, valid_plan));
95 MoveGroupInterface::Plan
plan = valid_plan;
97 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
102 MoveGroupInterface::Plan
plan = valid_plan;
104 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
109 MoveGroupInterface::Plan
plan = valid_plan;
111 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
116 MoveGroupInterface::Plan
plan = valid_plan;
118 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
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));
133 AlwaysInsertNeverPrunePolicy policy;
135 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>(
"test_db", policy.getName());
136 ASSERT_EQ(coll.count(), 0);
140 MoveGroupInterface::Plan
plan;
141 MoveItErrorCode ret = MoveItErrorCode::FAILURE;
144 MoveGroupInterface::Plan another_plan;
145 MoveItErrorCode another_ret = MoveItErrorCode::FAILURE;
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());
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
165 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, msg, plan);
166 ASSERT_TRUE(ret) << ret.message;
169 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, another_msg, another_plan);
170 ASSERT_TRUE(ret) << ret.message;
178 for (
const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
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"));
186 coll.insert(msg_plan_pair.second.trajectory, metadata);
187 coll.insert(msg_plan_pair.second.trajectory, metadata);
189 ASSERT_EQ(coll.count(), count);
196 std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>> features =
197 AlwaysInsertNeverPrunePolicy::getSupportedFeatures(0.025, 0.001);
199 for (
const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
201 Query::Ptr query = coll.createQuery();
202 for (
const auto& feature : features)
204 ASSERT_TRUE(feature->appendFeaturesAsExactFetchQuery(*query, msg_plan_pair.first, *move_group_,
208 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> feature_fetch =
209 coll.queryList(query,
true);
210 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> policy_fetch = policy.fetchMatchingEntries(
211 *move_group_, coll, msg_plan_pair.first, msg_plan_pair.second, 0.0001);
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)
217 ASSERT_EQ(*feature_fetch[i], *policy_fetch[i]);
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());
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());
242 CartesianAlwaysInsertNeverPrunePolicy policy;
244 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>(
"test_db", policy.getName());
246 GetCartesianPath::Request valid_msg;
247 GetCartesianPath::Response valid_plan;
248 valid_plan.fraction = -1;
252 std::vector<geometry_msgs::msg::Pose> waypoints;
253 waypoints.push_back(move_group_->getCurrentPose().pose);
254 waypoints.push_back(move_group_->getRandomPose().pose);
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);
267 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, valid_plan);
268 ASSERT_TRUE(ret) << ret.message;
276 GetCartesianPath::Request msg = valid_msg;
277 msg.waypoints.clear();
278 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, msg, valid_plan));
283 GetCartesianPath::Response
plan = valid_plan;
284 plan.solution.joint_trajectory.points.clear();
285 EXPECT_FALSE(policy.checkCacheInsertInputs(*move_group_, coll, valid_msg, plan));
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));
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));
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));
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));
321 CartesianAlwaysInsertNeverPrunePolicy policy;
323 MessageCollection<RobotTrajectory> coll = db_->openCollection<RobotTrajectory>(
"test_db", policy.getName());
324 ASSERT_EQ(coll.count(), 0);
327 GetCartesianPath::Request msg;
328 GetCartesianPath::Response
plan;
331 GetCartesianPath::Request another_msg;
332 GetCartesianPath::Response another_plan;
333 another_plan.fraction = -1;
337 std::vector<geometry_msgs::msg::Pose> waypoints;
338 waypoints.push_back(move_group_->getCurrentPose().pose);
339 waypoints.push_back(move_group_->getRandomPose().pose);
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);
352 std::vector<geometry_msgs::msg::Pose> waypoints;
353 waypoints.push_back(move_group_->getCurrentPose().pose);
354 waypoints.push_back(move_group_->getRandomPose().pose);
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);
368 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, msg, plan);
369 ASSERT_TRUE(ret) << ret.message;
372 MoveItErrorCode ret = policy.checkCacheInsertInputs(*move_group_, coll, another_msg, another_plan);
373 ASSERT_TRUE(ret) << ret.message;
381 for (
const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
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"));
389 coll.insert(msg_plan_pair.second.solution, metadata);
390 coll.insert(msg_plan_pair.second.solution, metadata);
392 ASSERT_EQ(coll.count(), count);
399 std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>> features =
400 CartesianAlwaysInsertNeverPrunePolicy::getSupportedFeatures(0.025,
404 for (
const auto& msg_plan_pair : { std::make_pair(msg, plan), std::make_pair(another_msg, another_plan) })
406 Query::Ptr query = coll.createQuery();
407 for (
const auto& feature : features)
409 ASSERT_TRUE(feature->appendFeaturesAsExactFetchQuery(*query, msg_plan_pair.first, *move_group_,
413 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> feature_fetch =
414 coll.queryList(query,
true);
415 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> policy_fetch = policy.fetchMatchingEntries(
416 *move_group_, coll, msg_plan_pair.first, msg_plan_pair.second, 0.0001);
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)
422 ASSERT_EQ(*feature_fetch[i], *policy_fetch[i]);
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());
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());
444 rclcpp::init(argc, argv);
445 ::testing::InitGoogleTest(&argc, argv);
446 int result = RUN_ALL_TESTS();
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
int main(int argc, char **argv)
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.