32#include <gtest/gtest.h>
33#include <warehouse_ros/message_collection.h>
36#include <moveit_msgs/msg/motion_plan_request.hpp>
41#include "../fixtures/move_group_fixture.hpp"
46using ::warehouse_ros::MessageCollection;
47using ::warehouse_ros::Metadata;
48using ::warehouse_ros::Query;
50using ::moveit_msgs::msg::MotionPlanRequest;
51using ::moveit_ros::trajectory_cache::FeaturesInterface;
53using ::moveit_ros::trajectory_cache::GoalConstraintsFeatures;
54using ::moveit_ros::trajectory_cache::MaxSpeedAndAccelerationFeatures;
55using ::moveit_ros::trajectory_cache::PathConstraintsFeatures;
56using ::moveit_ros::trajectory_cache::StartStateJointStateFeatures;
57using ::moveit_ros::trajectory_cache::TrajectoryConstraintsFeatures;
58using ::moveit_ros::trajectory_cache::WorkspaceFeatures;
63 double match_tolerance = 0.001;
65 std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>> features_under_test;
67 features_under_test.push_back(std::make_unique<GoalConstraintsFeatures>(match_tolerance));
68 features_under_test.push_back(std::make_unique<MaxSpeedAndAccelerationFeatures>());
69 features_under_test.push_back(std::make_unique<PathConstraintsFeatures>(match_tolerance));
70 features_under_test.push_back(std::make_unique<StartStateJointStateFeatures>(match_tolerance));
71 features_under_test.push_back(std::make_unique<TrajectoryConstraintsFeatures>(match_tolerance));
72 features_under_test.push_back(std::make_unique<WorkspaceFeatures>());
75 ASSERT_TRUE(move_group_->setPoseTarget(move_group_->getRandomPose()));
77 move_group_->constructMotionPlanRequest(msg);
80 for (
auto& feature : features_under_test)
82 MessageCollection<MotionPlanRequest> coll = db_->openCollection<
MotionPlanRequest>(
"test_db", feature->getName());
84 SCOPED_TRACE(feature->getName());
86 Query::Ptr fuzzy_query = coll.createQuery();
87 Query::Ptr exact_query = coll.createQuery();
88 Metadata::Ptr metadata = coll.createMetadata();
90 EXPECT_TRUE(feature->appendFeaturesAsInsertMetadata(*metadata, msg, *move_group_));
91 coll.insert(msg, metadata);
94 feature->appendFeaturesAsFuzzyFetchQuery(*fuzzy_query, msg, *move_group_, 0.0001));
96 feature->appendFeaturesAsExactFetchQuery(*exact_query, msg, *move_group_, 0.0001));
98 EXPECT_EQ(coll.queryList(fuzzy_query).size(), 1);
99 EXPECT_EQ(coll.queryList(exact_query).size(), 1);
107 rclcpp::init(argc, argv);
108 ::testing::InitGoogleTest(&argc, argv);
109 int result = RUN_ALL_TESTS();
Test fixture to spin up a node to start a move group with.
Abstract template class for extracting features from some FeatureSourceT.
moveit_msgs::msg::MotionPlanRequest features to key the trajectory cache on.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.
int main(int argc, char **argv)