|
15 | 15 |
|
16 | 16 | #include "gmock/gmock.h"
|
17 | 17 | #include "hardware_interface/component_parser.hpp"
|
| 18 | +#include "hardware_interface/handle.hpp" |
18 | 19 | #include "hardware_interface/types/hardware_interface_type_values.hpp"
|
19 | 20 | #include "ros2_control_test_assets/components_urdfs.hpp"
|
20 | 21 | #include "ros2_control_test_assets/descriptions.hpp"
|
@@ -980,6 +981,82 @@ TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_with_size_and_d
|
980 | 981 | EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].size, 1);
|
981 | 982 | }
|
982 | 983 |
|
| 984 | +TEST_F( |
| 985 | + TestComponentParser, |
| 986 | + successfully_parse_valid_urdf_system_with_bool_data_type_on_joint_sensor_and_gpio) |
| 987 | +{ |
| 988 | + std::string urdf_to_test = |
| 989 | + std::string(ros2_control_test_assets::urdf_head) + |
| 990 | + ros2_control_test_assets:: |
| 991 | + valid_urdf_ros2_control_system_robot_with_size_and_data_type_on_joint_sensor_and_gpio + |
| 992 | + ros2_control_test_assets::urdf_tail; |
| 993 | + const auto control_hardware = parse_control_resources_from_urdf(urdf_to_test); |
| 994 | + ASSERT_THAT(control_hardware, SizeIs(1)); |
| 995 | + auto hardware_info = control_hardware.front(); |
| 996 | + |
| 997 | + EXPECT_EQ(hardware_info.name, "RRBotSystemWithSizeAndDataType"); |
| 998 | + EXPECT_EQ(hardware_info.type, "system"); |
| 999 | + EXPECT_EQ( |
| 1000 | + hardware_info.hardware_plugin_name, |
| 1001 | + "ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType"); |
| 1002 | + |
| 1003 | + ASSERT_THAT(hardware_info.joints, SizeIs(1)); |
| 1004 | + ASSERT_FALSE(hardware_info.is_async); |
| 1005 | + ASSERT_EQ(hardware_info.thread_priority, std::numeric_limits<int>::max()); |
| 1006 | + EXPECT_EQ(hardware_info.joints[0].name, "joint1"); |
| 1007 | + EXPECT_EQ(hardware_info.joints[0].type, "joint"); |
| 1008 | + EXPECT_THAT(hardware_info.joints[0].command_interfaces, SizeIs(2)); |
| 1009 | + EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].name, HW_IF_POSITION); |
| 1010 | + EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].data_type, "double"); |
| 1011 | + EXPECT_EQ(hardware_info.joints[0].command_interfaces[0].size, 1); |
| 1012 | + EXPECT_EQ(hardware_info.joints[0].command_interfaces[1].name, "enable"); |
| 1013 | + EXPECT_EQ(hardware_info.joints[0].command_interfaces[1].data_type, "bool"); |
| 1014 | + EXPECT_EQ(hardware_info.joints[0].command_interfaces[1].size, 1); |
| 1015 | + hardware_interface::InterfaceDescription bool_cmd_description( |
| 1016 | + hardware_info.joints[0].name, hardware_info.joints[0].command_interfaces[1]); |
| 1017 | + auto bool_cmd_itf = hardware_interface::CommandInterface(bool_cmd_description); |
| 1018 | + ASSERT_EQ(hardware_interface::HandleDataType::BOOL, bool_cmd_itf.get_data_type()); |
| 1019 | + |
| 1020 | + EXPECT_THAT(hardware_info.joints[0].state_interfaces, SizeIs(2)); |
| 1021 | + EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].name, HW_IF_POSITION); |
| 1022 | + EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].data_type, "double"); |
| 1023 | + EXPECT_EQ(hardware_info.joints[0].state_interfaces[0].size, 1); |
| 1024 | + EXPECT_EQ(hardware_info.joints[0].state_interfaces[1].name, "status"); |
| 1025 | + EXPECT_EQ(hardware_info.joints[0].state_interfaces[1].data_type, "bool"); |
| 1026 | + EXPECT_EQ(hardware_info.joints[0].state_interfaces[1].size, 1); |
| 1027 | + hardware_interface::InterfaceDescription bool_state_description( |
| 1028 | + hardware_info.joints[0].name, hardware_info.joints[0].state_interfaces[1]); |
| 1029 | + auto bool_state_itf = hardware_interface::StateInterface(bool_state_description); |
| 1030 | + ASSERT_EQ(hardware_interface::HandleDataType::BOOL, bool_state_itf.get_data_type()); |
| 1031 | + |
| 1032 | + ASSERT_THAT(hardware_info.sensors, SizeIs(1)); |
| 1033 | + EXPECT_EQ(hardware_info.sensors[0].name, "trigger"); |
| 1034 | + EXPECT_EQ(hardware_info.sensors[0].type, "sensor"); |
| 1035 | + EXPECT_THAT(hardware_info.sensors[0].state_interfaces, SizeIs(1)); |
| 1036 | + EXPECT_EQ(hardware_info.sensors[0].state_interfaces[0].name, "safety"); |
| 1037 | + EXPECT_EQ(hardware_info.sensors[0].state_interfaces[0].data_type, "bool"); |
| 1038 | + EXPECT_EQ(hardware_info.sensors[0].state_interfaces[0].size, 1); |
| 1039 | + EXPECT_THAT(hardware_info.sensors[0].command_interfaces, SizeIs(1)); |
| 1040 | + EXPECT_EQ(hardware_info.sensors[0].command_interfaces[0].name, "safety"); |
| 1041 | + EXPECT_EQ(hardware_info.sensors[0].command_interfaces[0].data_type, "bool"); |
| 1042 | + EXPECT_EQ(hardware_info.sensors[0].command_interfaces[0].size, 1); |
| 1043 | + |
| 1044 | + ASSERT_THAT(hardware_info.gpios, SizeIs(1)); |
| 1045 | + EXPECT_EQ(hardware_info.gpios[0].name, "flange_IOS"); |
| 1046 | + EXPECT_EQ(hardware_info.gpios[0].type, "gpio"); |
| 1047 | + EXPECT_THAT(hardware_info.gpios[0].command_interfaces, SizeIs(1)); |
| 1048 | + EXPECT_EQ(hardware_info.gpios[0].command_interfaces[0].name, "digital_output"); |
| 1049 | + EXPECT_EQ(hardware_info.gpios[0].command_interfaces[0].data_type, "bool"); |
| 1050 | + EXPECT_EQ(hardware_info.gpios[0].command_interfaces[0].size, 2); |
| 1051 | + EXPECT_THAT(hardware_info.gpios[0].state_interfaces, SizeIs(2)); |
| 1052 | + EXPECT_EQ(hardware_info.gpios[0].state_interfaces[0].name, "analog_input"); |
| 1053 | + EXPECT_EQ(hardware_info.gpios[0].state_interfaces[0].data_type, "double"); |
| 1054 | + EXPECT_EQ(hardware_info.gpios[0].state_interfaces[0].size, 3); |
| 1055 | + EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].name, "image"); |
| 1056 | + EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].data_type, "cv::Mat"); |
| 1057 | + EXPECT_EQ(hardware_info.gpios[0].state_interfaces[1].size, 1); |
| 1058 | +} |
| 1059 | + |
983 | 1060 | TEST_F(TestComponentParser, successfully_parse_valid_urdf_system_and_disabled_interfaces)
|
984 | 1061 | {
|
985 | 1062 | std::string urdf_to_test =
|
|
0 commit comments