|
| 1 | +#include <gmock/gmock.h> |
| 2 | + |
| 3 | +#include <cmath> |
| 4 | +#include <string> |
| 5 | +#include <unordered_map> |
| 6 | +#include <vector> |
| 7 | + |
| 8 | +#include "hardware_interface/loaned_command_interface.hpp" |
| 9 | +#include "hardware_interface/loaned_state_interface.hpp" |
| 10 | +#include "hardware_interface/resource_manager.hpp" |
| 11 | +#include "hardware_interface/types/lifecycle_state_names.hpp" |
| 12 | +#include "lifecycle_msgs/msg/state.hpp" |
| 13 | +#include "rclcpp_lifecycle/state.hpp" |
| 14 | +#include "ros2_control_test_assets/components_urdfs.hpp" |
| 15 | +#include "ros2_control_test_assets/descriptions.hpp" |
| 16 | + |
| 17 | +namespace |
| 18 | +{ |
| 19 | +const auto TIME = rclcpp::Time(0); |
| 20 | +const auto PERIOD = rclcpp::Duration::from_seconds(0.1); // 0.1 seconds for easier math |
| 21 | +const auto COMPARE_DELTA = 0.0001; |
| 22 | +} // namespace |
| 23 | + |
| 24 | +class TestHWInterface : public ::testing::Test |
| 25 | +{ |
| 26 | +protected: |
| 27 | + void SetUp() override |
| 28 | + { |
| 29 | + hardware_system_2dof_ = |
| 30 | + R"( |
| 31 | + <ros2_control name="GenericSystem2dof" type="system"> |
| 32 | + <hardware> |
| 33 | + <plugin>mock_components/GenericSystem</plugin> |
| 34 | + </hardware> |
| 35 | + <joint name="joint1"> |
| 36 | + <command_interface name="position"/> |
| 37 | + <state_interface name="position"> |
| 38 | + <param name="initial_value">1.57</param> |
| 39 | + </state_interface> |
| 40 | + </joint> |
| 41 | + <joint name="joint2"> |
| 42 | + <command_interface name="position"/> |
| 43 | + <state_interface name="position"> |
| 44 | + <param name="initial_value">0.7854</param> |
| 45 | + </state_interface> |
| 46 | + </joint> |
| 47 | + </ros2_control> |
| 48 | +)"; |
| 49 | + } |
| 50 | + |
| 51 | + std::string hardware_system_2dof_; |
| 52 | +}; |
| 53 | + |
| 54 | +// Forward declaration |
| 55 | +namespace hardware_interface |
| 56 | +{ |
| 57 | +class ResourceStorage; |
| 58 | +} |
| 59 | + |
| 60 | +class TestableResourceManager : public hardware_interface::ResourceManager |
| 61 | +{ |
| 62 | +public: |
| 63 | + friend TestHWInterface; |
| 64 | + |
| 65 | + TestableResourceManager() : hardware_interface::ResourceManager() {} |
| 66 | + |
| 67 | + TestableResourceManager( |
| 68 | + const std::string & urdf, bool validate_interfaces = true, bool activate_all = false) |
| 69 | + : hardware_interface::ResourceManager(urdf, validate_interfaces, activate_all) |
| 70 | + { |
| 71 | + } |
| 72 | +}; |
| 73 | + |
| 74 | +TEST_F(TestHWInterface, load_generic_system_2dof) |
| 75 | +{ |
| 76 | + auto urdf = ros2_control_test_assets::urdf_head + hardware_system_2dof_ + |
| 77 | + ros2_control_test_assets::urdf_tail; |
| 78 | + ASSERT_NO_THROW(TestableResourceManager rm(urdf)); |
| 79 | +} |
0 commit comments