moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_utils_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
19#include <gtest/gtest.h>
20
23
24#include "../fixtures/move_group_fixture.hpp"
25
26namespace
27{
28
29TEST_F(MoveGroupFixture, GetWorkspaceFrameIdWorks)
30{
31 moveit_msgs::msg::WorkspaceParameters workspace_parameters;
32 EXPECT_EQ(moveit_ros::trajectory_cache::getWorkspaceFrameId(*move_group_, workspace_parameters),
33 move_group_->getRobotModel()->getModelFrame());
34
35 workspace_parameters.header.frame_id = "test_frame";
36 EXPECT_EQ(moveit_ros::trajectory_cache::getWorkspaceFrameId(*move_group_, workspace_parameters), "test_frame");
37}
38
39TEST_F(MoveGroupFixture, GetCartesianPathRequestFrameId)
40{
41 moveit_msgs::srv::GetCartesianPath::Request path_request;
42 EXPECT_EQ(moveit_ros::trajectory_cache::getCartesianPathRequestFrameId(*move_group_, path_request),
43 move_group_->getPoseReferenceFrame());
44
45 path_request.header.frame_id = "test_frame";
46 EXPECT_EQ(moveit_ros::trajectory_cache::getCartesianPathRequestFrameId(*move_group_, path_request), "test_frame");
47}
48
49} // namespace
50
51int main(int argc, char** argv)
52{
53 rclcpp::init(argc, argv);
54 ::testing::InitGoogleTest(&argc, argv);
55 int result = RUN_ALL_TESTS();
56 rclcpp::shutdown();
57 return result;
58}
Test fixture to spin up a node to start a move group with.
Utilities used by the trajectory_cache package.
std::string getWorkspaceFrameId(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::WorkspaceParameters &workspace_parameters)
Gets workspace frame ID. If workspace_parameters has no frame ID, fetch it from move_group.
std::string getCartesianPathRequestFrameId(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &path_request)
Gets cartesian path request frame ID. If path_request has no frame ID, fetch it from move_group.
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.
int main(int argc, char **argv)