Skip to content

Commit

Permalink
Fix the test_component_interface for missing valid node_clock_interface
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Aug 7, 2024
1 parent 57da131 commit 93c33e2
Showing 1 changed file with 35 additions and 18 deletions.
53 changes: 35 additions & 18 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

// Values to send over command interface to trigger error in write and read methods
Expand Down Expand Up @@ -424,8 +425,9 @@ TEST(TestComponentInterfaces, dummy_actuator)
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components");
auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
auto state =
actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -515,8 +517,9 @@ TEST(TestComponentInterfaces, dummy_sensor)
hardware_interface::Sensor sensor_hw(std::make_unique<test_components::DummySensor>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_components");
auto state = sensor_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_components");
auto state =
sensor_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -547,8 +550,9 @@ TEST(TestComponentInterfaces, dummy_system)
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -672,8 +676,9 @@ TEST(TestComponentInterfaces, dummy_command_mode_system)
hardware_interface::System system_hw(
std::make_unique<test_components::DummySystemPreparePerform>());
hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -704,8 +709,9 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior)
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components");
auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
auto state =
actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -764,8 +770,9 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior)
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components");
auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_components");
auto state =
actuator_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -824,8 +831,9 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior)
hardware_interface::Sensor sensor_hw(std::make_unique<test_components::DummySensor>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_components");
auto state = sensor_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_components");
auto state =
sensor_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());

auto state_interfaces = sensor_hw.export_state_interfaces();
// Updated because is is INACTIVE
Expand Down Expand Up @@ -889,8 +897,9 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior)
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -954,8 +963,9 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());

hardware_interface::HardwareInfo mock_hw_info{};
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(mock_hw_info, node->get_logger(), node->get_node_clock_interface());
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -1013,3 +1023,10 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::FINALIZED, state.label());
}

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

0 comments on commit 93c33e2

Please sign in to comment.