moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_scene_monitor_test.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, University of Hamburg
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Michael 'v4hn' Goerner
36 Desc: Tests for PlanningSceneMonitor
37*/
38
39// ROS
40#include <rclcpp/rclcpp.hpp>
41
42// Testing
43#include <gtest/gtest.h>
44
45// Main class
48
49class PlanningSceneMonitorTest : public ::testing::Test
50{
51public:
52 void SetUp() override
53 {
54 test_node_ = std::make_shared<rclcpp::Node>("moveit_planning_scene_monitor_test");
55 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
56 planning_scene_monitor_ = std::make_unique<planning_scene_monitor::PlanningSceneMonitor>(
57 test_node_, "robot_description", "planning_scene_monitor");
58 planning_scene_monitor_->monitorDiffs(true);
59 scene_ = planning_scene_monitor_->getPlanningScene();
60 executor_->add_node(test_node_);
61 executor_thread_ = std::thread([this]() { executor_->spin(); });
62 }
63
64 void TearDown() override
65 {
66 scene_.reset();
67 executor_->cancel();
68 if (executor_thread_.joinable())
69 {
70 executor_thread_.join();
71 }
72 }
73
74protected:
75 std::shared_ptr<rclcpp::Node> test_node_;
76
77 // Executor and a thread to run the executor.
78 rclcpp::Executor::SharedPtr executor_;
79 std::thread executor_thread_;
80
81 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
82 planning_scene::PlanningScenePtr scene_;
83};
84
85// various code expects the monitored scene to remain the same
86TEST_F(PlanningSceneMonitorTest, TestPersistentScene)
87{
88 auto scene{ planning_scene_monitor_->getPlanningScene() };
89 moveit_msgs::msg::PlanningScene msg;
90 msg.is_diff = msg.robot_state.is_diff = true;
91 planning_scene_monitor_->newPlanningSceneMessage(msg);
92 EXPECT_EQ(scene, planning_scene_monitor_->getPlanningScene());
93 msg.is_diff = msg.robot_state.is_diff = false;
94 planning_scene_monitor_->newPlanningSceneMessage(msg);
95 EXPECT_EQ(scene, planning_scene_monitor_->getPlanningScene());
96}
97
99
100#define TRIGGERS_UPDATE(msg, expected_update_type) \
101 { \
102 planning_scene_monitor_->clearUpdateCallbacks(); \
103 auto received_update_type{ UpdateType::UPDATE_NONE }; \
104 planning_scene_monitor_->addUpdateCallback([&](auto type) { received_update_type = type; }); \
105 planning_scene_monitor_->newPlanningSceneMessage(msg); \
106 EXPECT_EQ(received_update_type, expected_update_type); \
107 }
108
110{
111 moveit_msgs::msg::PlanningScene msg;
112 msg.is_diff = msg.robot_state.is_diff = true;
113 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_NONE);
114
115 msg.fixed_frame_transforms.emplace_back();
116 msg.fixed_frame_transforms.back().header.frame_id = "base_link";
117 msg.fixed_frame_transforms.back().child_frame_id = "object";
118 msg.fixed_frame_transforms.back().transform.rotation.w = 1.0;
119 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_TRANSFORMS);
120 msg.fixed_frame_transforms.clear();
121 moveit::core::robotStateToRobotStateMsg(scene_->getCurrentState(), msg.robot_state, false);
122 msg.robot_state.is_diff = true;
123 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_STATE);
124
125 msg.robot_state.is_diff = false;
126 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_STATE | UpdateType::UPDATE_GEOMETRY);
127
128 msg.robot_state = moveit_msgs::msg::RobotState{};
129 msg.robot_state.is_diff = true;
130 moveit_msgs::msg::CollisionObject collision_object;
131 collision_object.header.frame_id = "base_link";
132 collision_object.id = "object";
133 collision_object.operation = moveit_msgs::msg::CollisionObject::ADD;
134 collision_object.pose.orientation.w = 1.0;
135 collision_object.primitives.emplace_back();
136 collision_object.primitives.back().type = shape_msgs::msg::SolidPrimitive::SPHERE;
137 collision_object.primitives.back().dimensions = { 1.0 };
138 msg.world.collision_objects.emplace_back(collision_object);
139 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_GEOMETRY);
140
141 msg.world.collision_objects.clear();
142 msg.is_diff = false;
143
144 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_SCENE);
145}
146
147int main(int argc, char** argv)
148{
149 rclcpp::init(argc, argv);
150 ::testing::InitGoogleTest(&argc, argv);
151 int result = RUN_ALL_TESTS();
152 rclcpp::shutdown();
153 return result;
154}
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
rclcpp::Executor::SharedPtr executor_
planning_scene::PlanningScenePtr scene_
std::shared_ptr< rclcpp::Node > test_node_
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
int main(int argc, char **argv)
TEST_F(PlanningSceneMonitorTest, TestPersistentScene)
#define TRIGGERS_UPDATE(msg, expected_update_type)