Skip to content

Commit

Permalink
Add small behavior fixes.
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Jan 26, 2024
1 parent 44d2ee4 commit 7bb83b6
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 12 deletions.
16 changes: 8 additions & 8 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,6 +295,14 @@ void ControllerManager::init_controller_manager()
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
}

robot_description_notification_timer_ = create_wall_timer(
std::chrono::seconds(1),
[&]()
{
RCLCPP_WARN(
get_logger(), "Waiting for data on '~/robot_description' topic to finish initialization");
});

// set QoS to transient local to get messages that have already been published
// (if robot state publisher starts before controller manager)
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
Expand All @@ -308,14 +316,6 @@ void ControllerManager::init_controller_manager()
diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);

robot_description_notification_timer_ = create_wall_timer(
std::chrono::seconds(1),
[&]()
{
RCLCPP_WARN(
get_logger(), "Waiting for data on '~/robot_description' topic to finish initialization");
});
}

void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description)
Expand Down
6 changes: 2 additions & 4 deletions hardware_interface_testing/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,17 +106,15 @@ TEST_F(ResourceManagerTest, test_unitilizable_hardware_validation)
// If the the hardware can not be initialized and load_urdf tried to validate the interfaces a
// runtime exception is thrown
TestableResourceManager rm;
ASSERT_THROW(
rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, true),
std::runtime_error);
EXPECT_FALSE(rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, true));
}

TEST_F(ResourceManagerTest, test_unitilizable_hardware_no_validation)
{
// If the the hardware can not be initialized and load_urdf didn't try to validate the interfaces,
// the interface should not show up
TestableResourceManager rm;
EXPECT_NO_THROW(rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, false));
EXPECT_TRUE(rm.load_urdf(ros2_control_test_assets::minimal_unitilizable_robot_urdf, false));

// test actuator
EXPECT_FALSE(rm.state_interface_exists("joint1/position"));
Expand Down

0 comments on commit 7bb83b6

Please sign in to comment.