32#include <gtest/gtest.h>
33#include <warehouse_ros/message_collection.h>
36#include <moveit_msgs/srv/get_cartesian_path.hpp>
42#include "../fixtures/move_group_fixture.hpp"
47using ::warehouse_ros::MessageCollection;
48using ::warehouse_ros::Metadata;
49using ::warehouse_ros::Query;
51using ::moveit_msgs::srv::GetCartesianPath;
53using ::moveit_ros::trajectory_cache::constructGetCartesianPathRequest;
54using ::moveit_ros::trajectory_cache::FeaturesInterface;
56using ::moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures;
57using ::moveit_ros::trajectory_cache::CartesianMaxStepAndJumpThresholdFeatures;
58using ::moveit_ros::trajectory_cache::CartesianPathConstraintsFeatures;
59using ::moveit_ros::trajectory_cache::CartesianStartStateJointStateFeatures;
60using ::moveit_ros::trajectory_cache::CartesianWaypointsFeatures;
61using ::moveit_ros::trajectory_cache::CartesianWorkspaceFeatures;
66 double match_tolerance = 0.001;
68 std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>> features_under_test;
70 features_under_test.push_back(std::make_unique<CartesianMaxSpeedAndAccelerationFeatures>());
71 features_under_test.push_back(std::make_unique<CartesianMaxStepAndJumpThresholdFeatures>());
72 features_under_test.push_back(std::make_unique<CartesianPathConstraintsFeatures>(match_tolerance));
73 features_under_test.push_back(std::make_unique<CartesianStartStateJointStateFeatures>(match_tolerance));
74 features_under_test.push_back(std::make_unique<CartesianWaypointsFeatures>(match_tolerance));
75 features_under_test.push_back(std::make_unique<CartesianWorkspaceFeatures>());
78 std::vector<geometry_msgs::msg::Pose> waypoints = { move_group_->getRandomPose().pose,
79 move_group_->getRandomPose().pose };
85 for (
auto& feature : features_under_test)
87 MessageCollection<GetCartesianPath::Request> coll =
88 db_->openCollection<GetCartesianPath::Request>(
"test_db", feature->getName());
90 SCOPED_TRACE(feature->getName());
92 Query::Ptr fuzzy_query = coll.createQuery();
93 Query::Ptr exact_query = coll.createQuery();
94 Metadata::Ptr metadata = coll.createMetadata();
96 EXPECT_TRUE(feature->appendFeaturesAsInsertMetadata(*metadata, msg, *move_group_));
97 coll.insert(msg, metadata);
100 feature->appendFeaturesAsFuzzyFetchQuery(*fuzzy_query, msg, *move_group_, 0.0001));
102 feature->appendFeaturesAsExactFetchQuery(*exact_query, msg, *move_group_, 0.0001));
104 EXPECT_EQ(coll.queryList(fuzzy_query).size(), 1);
105 EXPECT_EQ(coll.queryList(exact_query).size(), 1);
113 rclcpp::init(argc, argv);
114 ::testing::InitGoogleTest(&argc, argv);
115 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::srv::GetCartesianPath::Request features to key the trajectory cache on.
Utilities used by the trajectory_cache package.
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.
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.
int main(int argc, char **argv)