moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_get_cartesian_path_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/srv/get_cartesian_path.hpp>
37
41
42#include "../fixtures/move_group_fixture.hpp"
43
44namespace
45{
46
47using ::warehouse_ros::MessageCollection;
48using ::warehouse_ros::Metadata;
49using ::warehouse_ros::Query;
50
51using ::moveit_msgs::srv::GetCartesianPath;
52
53using ::moveit_ros::trajectory_cache::constructGetCartesianPathRequest;
54using ::moveit_ros::trajectory_cache::FeaturesInterface;
55
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;
62
63TEST_F(MoveGroupFixture, GetCartesianPathRequestRoundTrip)
64{
65 // Test cases.
66 double match_tolerance = 0.001;
67
68 std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>> features_under_test;
69
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>());
76
77 // Setup.
78 std::vector<geometry_msgs::msg::Pose> waypoints = { move_group_->getRandomPose().pose,
79 move_group_->getRandomPose().pose };
80
81 GetCartesianPath::Request msg = constructGetCartesianPathRequest(*move_group_, waypoints, /*max_step=*/1.0,
82 /*jump_threshold=*/0.0, /*avoid_collisions=*/false);
83
84 // Core test.
85 for (auto& feature : features_under_test)
86 {
87 MessageCollection<GetCartesianPath::Request> coll =
88 db_->openCollection<GetCartesianPath::Request>("test_db", feature->getName());
89
90 SCOPED_TRACE(feature->getName());
91
92 Query::Ptr fuzzy_query = coll.createQuery();
93 Query::Ptr exact_query = coll.createQuery();
94 Metadata::Ptr metadata = coll.createMetadata();
95
96 EXPECT_TRUE(feature->appendFeaturesAsInsertMetadata(*metadata, msg, *move_group_));
97 coll.insert(msg, metadata);
98
99 EXPECT_TRUE(
100 feature->appendFeaturesAsFuzzyFetchQuery(*fuzzy_query, msg, *move_group_, /*exact_match_precision=*/0.0001));
101 EXPECT_TRUE(
102 feature->appendFeaturesAsExactFetchQuery(*exact_query, msg, *move_group_, /*exact_match_precision=*/0.0001));
103
104 EXPECT_EQ(coll.queryList(fuzzy_query).size(), 1);
105 EXPECT_EQ(coll.queryList(exact_query).size(), 1);
106 }
107}
108
109} // namespace
110
111int main(int argc, char** argv)
112{
113 rclcpp::init(argc, argv);
114 ::testing::InitGoogleTest(&argc, argv);
115 int result = RUN_ALL_TESTS();
116 rclcpp::shutdown();
117 return result;
118}
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.