moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_controllers.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, Metro Robots
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 Metro Robots 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: David V. Lu!! */
40 
41 static const rclcpp::Logger LOGGER = rclcpp::get_logger("test_controllers");
42 
48 
50 {
51 protected:
52  void SetUp() override
53  {
54  MoveItSetupTest::SetUp();
55  config_data_->registerType("moveit_controllers", "moveit_setup::controllers::MoveItControllersConfig");
56  config_data_->registerType("ros2_controllers", "moveit_setup::controllers::ROS2ControllersConfig");
57  config_data_->registerType("modified_urdf", "moveit_setup::ModifiedUrdfConfig");
58  config_data_->registerType("control_xacro", "moveit_setup::controllers::ControlXacroConfig");
59  }
60 };
61 
62 TEST_F(ControllersTest, ParseFanuc)
63 {
64  config_data_->preloadWithFullConfig("moveit_resources_fanuc_moveit_config");
65  auto ros2_controllers_config = config_data_->get<ROS2ControllersConfig>("ros2_controllers");
66  const std::vector<ControllerInfo>& controllers = ros2_controllers_config->getControllers();
67  ASSERT_EQ(1u, controllers.size());
68  const ControllerInfo& ci = controllers[0];
69  EXPECT_EQ("fanuc_controller", ci.name_);
70  EXPECT_EQ("joint_trajectory_controller/JointTrajectoryController", ci.type_);
71  EXPECT_EQ(6u, ci.joints_.size());
72 
73  auto moveit_controllers_config = config_data_->get<MoveItControllersConfig>("moveit_controllers");
74  const std::vector<ControllerInfo>& mcontrollers = moveit_controllers_config->getControllers();
75  ASSERT_EQ(1u, mcontrollers.size());
76  const ControllerInfo& mci = mcontrollers[0];
77  EXPECT_EQ("fanuc_controller", mci.name_);
78  EXPECT_EQ("FollowJointTrajectory", mci.type_);
79  EXPECT_EQ(6u, mci.joints_.size());
80 }
81 
82 TEST_F(ControllersTest, ParsePanda)
83 {
84  config_data_->preloadWithFullConfig("moveit_resources_panda_moveit_config");
85  auto ros2_controllers_config = config_data_->get<ROS2ControllersConfig>("ros2_controllers");
86  const std::vector<ControllerInfo>& controllers = ros2_controllers_config->getControllers();
87  ASSERT_EQ(2u, controllers.size());
88 
89  int offset = controllers[0].name_ == "panda_arm_controller" ? 0 : 1;
90  const ControllerInfo& ci1 = controllers[offset];
91  EXPECT_EQ("panda_arm_controller", ci1.name_);
92  EXPECT_EQ("joint_trajectory_controller/JointTrajectoryController", ci1.type_);
93  EXPECT_EQ(7u, ci1.joints_.size());
94 
95  const ControllerInfo& ci2 = controllers[1 - offset];
96  EXPECT_EQ("panda_hand_controller", ci2.name_);
97  EXPECT_EQ("position_controllers/GripperActionController", ci2.type_);
98  EXPECT_EQ(1u, ci2.joints_.size());
99 
100  /*
101  TODO(dlu): Re-enable when moveit_resources 2.0.5 is available on the build farm
102 
103  auto moveit_controllers_config = config_data_->get<MoveItControllersConfig>("moveit_controllers");
104  const std::vector<ControllerInfo>& mcontrollers = moveit_controllers_config->getControllers();
105  ASSERT_EQ(1u, mcontrollers.size());
106  const ControllerInfo& mci1 = mcontrollers[offset];
107  EXPECT_EQ("panda_arm_controller", mci1.name_);
108  EXPECT_EQ("FollowJointTrajectory", mci1.type_);
109  EXPECT_EQ(7u, mci1.joints_.size());
110  */
111 }
112 
113 TEST_F(ControllersTest, OutputFanuc)
114 {
115  config_data_->preloadWithFullConfig("moveit_resources_fanuc_moveit_config");
116  config_data_->get<moveit_setup::controllers::ControlXacroConfig>("control_xacro")->loadFromDescription();
117  generateFiles<ROS2ControllersConfig>("ros2_controllers");
118  generateFiles<MoveItControllersConfig>("moveit_controllers");
119 
120  std::filesystem::path original_config = getSharePath("moveit_resources_fanuc_moveit_config");
121  for (const std::string relative_path : { "config/moveit_controllers.yaml", "config/ros2_controllers.yaml" })
122  {
123  expectYamlEquivalence(output_dir_ / relative_path, original_config / relative_path);
124  }
125 }
126 
127 TEST_F(ControllersTest, AddDefaultControllers)
128 {
129  // only preload urdf and srdf
130  auto config_dir = getSharePath("moveit_resources_panda_moveit_config");
131  YAML::Node settings = YAML::LoadFile(config_dir / ".setup_assistant")["moveit_setup_assistant_config"];
132  config_data_->get<moveit_setup::URDFConfig>("urdf")->loadPrevious(config_dir, settings["URDF"]);
133  auto srdf_config = config_data_->get<moveit_setup::SRDFConfig>("srdf");
134  srdf_config->loadPrevious(config_dir, settings["SRDF"]);
135 
136  auto ros2_controllers_config = config_data_->get<ROS2ControllersConfig>("ros2_controllers");
137 
138  // Initially no controllers
139  EXPECT_EQ(ros2_controllers_config->getControllers().size(), 0u);
140 
141  // Run the setup step
143  initializeStep(setup_step);
144 
145  // Adding default controllers, a controller for each planning group
146  setup_step.addDefaultControllers();
147 
148  // Number of the planning groups defined in the model srdf
149  size_t group_count = srdf_config->getGroups().size();
150 
151  // Test that addDefaultControllers() did accually add a controller for the new_group
152  EXPECT_EQ(ros2_controllers_config->getControllers().size(), group_count);
153 }
154 
155 int main(int argc, char** argv)
156 {
157  testing::InitGoogleTest(&argc, argv);
158  rclcpp::init(argc, argv);
159  return RUN_ALL_TESTS();
160 }
void SetUp() override
Test environment with DataWarehouse setup and help for generating files in a temp dir.
moveit_setup::DataWarehousePtr config_data_
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
Definition: srdf_config.cpp:47
std::vector< ControllerInfo > & getControllers()
Gets controllers_ vector.
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
Definition: utilities.hpp:50
void expectYamlEquivalence(const YAML::Node &generated, const YAML::Node &reference, const std::filesystem::path &generated_path, const std::string &yaml_namespace="")
const rclcpp::Logger LOGGER
Definition: async_test.h:31
TEST_F(ControllersTest, ParseFanuc)
int main(int argc, char **argv)