moveit_config_data_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Mohamad Ayman.
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 Willow Garage 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: Mohamad Ayman */
36 #include <gtest/gtest.h>
37 #include <sstream>
38 #include <ctype.h>
39 #include <iostream> // For writing yaml and launch files
40 #include <urdf_parser/urdf_parser.h>
41 #include <fstream>
42 #include <string>
43 #include <boost/filesystem/path.hpp>
44 #include <boost/filesystem/operations.hpp>
47 #include <ros/package.h>
48 
49 // This tests writing/parsing of ros_controller.yaml
50 class MoveItConfigData : public testing::Test
51 {
52 protected:
53  void SetUp() override
54  {
55  std::string robot_name = "panda";
58  robot_model_ = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_model_);
59  };
60 
61 protected:
62  urdf::ModelInterfaceSharedPtr urdf_model_;
64  moveit::core::RobotModelPtr robot_model_;
65 };
66 
67 TEST_F(MoveItConfigData, ReadingControllers)
68 {
69  // Contains all the configuration data for the setup assistant
70  moveit_setup_assistant::MoveItConfigDataPtr config_data;
71 
72  config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
73  config_data->srdf_->srdf_model_ = srdf_model_;
74  config_data->setRobotModel(robot_model_);
75 
76  // Initially no controllers
77  EXPECT_EQ(config_data->getControllers().size(), 0u);
78 
79  // Adding default controllers, a controller for each planning group
80  config_data->addDefaultControllers();
81 
82  // Number of the planning groups defined in the model srdf
83  size_t group_count = config_data->srdf_->srdf_model_->getGroups().size();
84 
85  // Test that addDefaultControllers() did accually add a controller for the new_group
86  EXPECT_EQ(config_data->getControllers().size(), group_count);
87 
88  // Temporary file used during the test and is deleted when the test is finished
89  char test_file[] = "/tmp/msa_unittest_ros_controller.yaml";
90 
91  // ros_controller.yaml written correctly
92  EXPECT_EQ(config_data->outputROSControllersYAML(test_file), true);
93 
94  // Reset MoveIt config MoveItConfigData
95  config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
96 
97  // Initially no controllers
98  EXPECT_EQ(config_data->getControllers().size(), 0u);
99 
100  // ros_controllers.yaml read correctly
101  EXPECT_EQ(config_data->inputROSControllersYAML(test_file), true);
102 
103  // ros_controllers.yaml parsed correctly
104  EXPECT_EQ(config_data->getControllers().size(), group_count);
105 
106  // Remove ros_controllers.yaml temp file which was used in testing
107  boost::filesystem::remove(test_file);
108 }
109 
110 // This tests parsing of sensors_3d.yaml
111 TEST_F(MoveItConfigData, ReadingSensorsConfig)
112 {
113  // Contains all the config data for the setup assistant
114  moveit_setup_assistant::MoveItConfigDataPtr config_data;
115  config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
116 
117  boost::filesystem::path setup_assistant_path(config_data->setup_assistant_path_);
118 
119  // Before parsing, no config available
120  EXPECT_EQ(config_data->getSensorPluginConfig().size(), 0u);
121 
122  // Read the file containing the default config parameters
123  config_data->input3DSensorsYAML(
124  (setup_assistant_path / "templates/moveit_config_pkg_template/config/sensors_3d.yaml").string());
125  auto configs = config_data->getSensorPluginConfig();
126 
127  // Default config for the two available sensor plugins
128  // Make sure both are parsed correctly
129  ASSERT_EQ(configs.size(), 2u);
130 
131  EXPECT_EQ(configs[0]["sensor_plugin"].getValue(), std::string("occupancy_map_monitor/PointCloudOctomapUpdater"));
132 
133  EXPECT_EQ(configs[1]["sensor_plugin"].getValue(), std::string("occupancy_map_monitor/DepthImageOctomapUpdater"));
134 }
135 
136 // This tests writing of sensors_3d.yaml
137 TEST_F(MoveItConfigData, WritingSensorsConfig)
138 {
139  // Contains all the config data for the setup assistant
140  moveit_setup_assistant::MoveItConfigDataPtr config_data;
141  config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
142 
143  // Empty Config Should have No Sensors
144  EXPECT_EQ(config_data->getSensorPluginConfig().size(), 0u);
145 
146  // Temporary file used during the test and is deleted when the test is finished
147  char test_file[] = "/tmp/msa_unittest_sensors.yaml";
148 
149  // empty sensors.yaml written correctly
150  EXPECT_EQ(config_data->output3DSensorPluginYAML(test_file), true);
151 
152  // Set default file
153  std::string default_file_path =
154  config_data->setup_assistant_path_ + "/templates/moveit_config_pkg_template/config/sensors_3d.yaml";
155 
156  // Read from the written (empty) file
158  // Should have No Sensors
159  EXPECT_EQ(config.size(), 0u);
160 
161  // Now load the default file and write it to a file
162  config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
163  config_data->input3DSensorsYAML(default_file_path);
164  EXPECT_EQ(config_data->getSensorPluginConfig().size(), 2u);
165  EXPECT_EQ(config_data->output3DSensorPluginYAML(test_file), true);
166 
167  // Read from the written file
169  EXPECT_EQ(config.size(), 2u);
170 }
171 
172 int main(int argc, char** argv)
173 {
174  testing::InitGoogleTest(&argc, argv);
175  return RUN_ALL_TESTS();
176 }
MoveItConfigData
Definition: moveit_config_data_test.cpp:50
srdf::ModelSharedPtr
std::shared_ptr< Model > ModelSharedPtr
TEST_F
TEST_F(MoveItConfigData, ReadingControllers)
Definition: moveit_config_data_test.cpp:67
moveit::core::loadModelInterface
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
moveit_config_data.h
MoveItConfigData::SetUp
void SetUp() override
Definition: moveit_config_data_test.cpp:85
MoveItConfigData::robot_model_
moveit::core::RobotModelPtr robot_model_
Definition: moveit_config_data_test.cpp:96
package.h
moveit_setup_assistant::MoveItConfigData::load3DSensorsYAML
static std::vector< std::map< std::string, GenericParameter > > load3DSensorsYAML(const std::string &file_path)
Load perception sensor config.
Definition: moveit_config_data.cpp:1863
moveit::core::loadSRDFModel
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
robot_model_test_utils.h
MoveItConfigData::urdf_model_
urdf::ModelInterfaceSharedPtr urdf_model_
Definition: moveit_config_data_test.cpp:91
config
config
main
int main(int argc, char **argv)
Definition: moveit_config_data_test.cpp:172
EXPECT_EQ
#define EXPECT_EQ(a, b)
MoveItConfigData::srdf_model_
srdf::ModelSharedPtr srdf_model_
Definition: moveit_config_data_test.cpp:95


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Sat May 3 2025 02:28:04