moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_motion_plan_request_features_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 
30 #include <memory>
31 
32 #include <gtest/gtest.h>
33 #include <warehouse_ros/message_collection.h>
34 
36 #include <moveit_msgs/msg/motion_plan_request.hpp>
37 
40 
41 #include "../fixtures/move_group_fixture.hpp"
42 
43 namespace
44 {
45 
46 using ::warehouse_ros::MessageCollection;
47 using ::warehouse_ros::Metadata;
48 using ::warehouse_ros::Query;
49 
51 using ::moveit_ros::trajectory_cache::FeaturesInterface;
52 
53 using ::moveit_ros::trajectory_cache::GoalConstraintsFeatures;
54 using ::moveit_ros::trajectory_cache::MaxSpeedAndAccelerationFeatures;
55 using ::moveit_ros::trajectory_cache::PathConstraintsFeatures;
56 using ::moveit_ros::trajectory_cache::StartStateJointStateFeatures;
57 using ::moveit_ros::trajectory_cache::TrajectoryConstraintsFeatures;
58 using ::moveit_ros::trajectory_cache::WorkspaceFeatures;
59 
60 TEST_F(MoveGroupFixture, MotionPlanRequestRoundTrip)
61 {
62  // Test cases.
63  double match_tolerance = 0.001;
64 
65  std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>> features_under_test;
66 
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>());
73 
74  // Setup.
75  ASSERT_TRUE(move_group_->setPoseTarget(move_group_->getRandomPose()));
77  move_group_->constructMotionPlanRequest(msg);
78 
79  // Core test.
80  for (auto& feature : features_under_test)
81  {
82  MessageCollection<MotionPlanRequest> coll = db_->openCollection<MotionPlanRequest>("test_db", feature->getName());
83 
84  SCOPED_TRACE(feature->getName());
85 
86  Query::Ptr fuzzy_query = coll.createQuery();
87  Query::Ptr exact_query = coll.createQuery();
88  Metadata::Ptr metadata = coll.createMetadata();
89 
90  EXPECT_TRUE(feature->appendFeaturesAsInsertMetadata(*metadata, msg, *move_group_));
91  coll.insert(msg, metadata);
92 
93  EXPECT_TRUE(
94  feature->appendFeaturesAsFuzzyFetchQuery(*fuzzy_query, msg, *move_group_, /*exact_match_precision=*/0.0001));
95  EXPECT_TRUE(
96  feature->appendFeaturesAsExactFetchQuery(*exact_query, msg, *move_group_, /*exact_match_precision=*/0.0001));
97 
98  EXPECT_EQ(coll.queryList(fuzzy_query).size(), 1);
99  EXPECT_EQ(coll.queryList(exact_query).size(), 1);
100  }
101 }
102 
103 } // namespace
104 
105 int main(int argc, char** argv)
106 {
107  rclcpp::init(argc, argv);
108  ::testing::InitGoogleTest(&argc, argv);
109  int result = RUN_ALL_TESTS();
110  rclcpp::shutdown();
111  return result;
112 }
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)