Skip to content

Commit

Permalink
Fix test_component_interfaces for newly added tests
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Nov 25, 2024
1 parent 7437630 commit bc47f7d
Show file tree
Hide file tree
Showing 2 changed files with 41 additions and 22 deletions.
40 changes: 24 additions & 16 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -783,8 +783,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component");
auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
actuator_hw.initialize(dummy_actuator, 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 @@ -938,8 +939,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component");
auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
sensor_hw.initialize(voltage_sensor_res, 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 @@ -1110,8 +1112,9 @@ TEST(TestComponentInterfaces, dummy_system_default)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_system_component");
auto state = system_hw.initialize(dummy_system, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(dummy_system, 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 @@ -1407,8 +1410,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_read_error_behavior)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component");
auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
actuator_hw.initialize(dummy_actuator, 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 @@ -1541,8 +1545,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_write_error_behavior)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component");
auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
actuator_hw.initialize(dummy_actuator, 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 @@ -1678,8 +1683,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_read_error_behavior)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component");
auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
sensor_hw.initialize(voltage_sensor_res, 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 @@ -1806,8 +1812,9 @@ TEST(TestComponentInterfaces, dummy_system_default_read_error_behavior)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_system_component");
auto state = system_hw.initialize(dummy_system, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(dummy_system, 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 @@ -1945,8 +1952,9 @@ TEST(TestComponentInterfaces, dummy_system_default_write_error_behavior)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_system_component");
auto state = system_hw.initialize(dummy_system, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_components");
auto state =
system_hw.initialize(dummy_system, 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
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,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"
#include "ros2_control_test_assets/components_urdfs.hpp"
#include "ros2_control_test_assets/descriptions.hpp"
Expand Down Expand Up @@ -169,8 +170,9 @@ TEST(TestComponentInterfaces, dummy_actuator_default_custom_export)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_actuator = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_component");
auto state = actuator_hw.initialize(dummy_actuator, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_actuator_component");
auto state =
actuator_hw.initialize(dummy_actuator, 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 @@ -234,8 +236,9 @@ TEST(TestComponentInterfaces, dummy_sensor_default_custom_export)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo voltage_sensor_res = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_component");
auto state = sensor_hw.initialize(voltage_sensor_res, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_sensor_component");
auto state =
sensor_hw.initialize(voltage_sensor_res, 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 @@ -271,8 +274,9 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export)
const std::vector<hardware_interface::HardwareInfo> control_resources =
hardware_interface::parse_control_resources_from_urdf(urdf_to_test);
const hardware_interface::HardwareInfo dummy_system = control_resources[0];
rclcpp::Logger logger = rclcpp::get_logger("test_system_component");
auto state = system_hw.initialize(dummy_system, logger, nullptr);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("test_system_component");
auto state =
system_hw.initialize(dummy_system, 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 @@ -373,3 +377,10 @@ TEST(TestComponentInterfaces, dummy_system_default_custom_export)
EXPECT_EQ("joint1", command_interfaces[position]->get_prefix_name());
}
}

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

0 comments on commit bc47f7d

Please sign in to comment.