Skip to content

Commit

Permalink
Fixed compilation and tests.
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Jan 31, 2024
1 parent c47ac65 commit c1ba8bc
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 84 deletions.
1 change: 0 additions & 1 deletion controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,6 @@ if(BUILD_TESTING)
)
target_link_libraries(test_controller_manager_urdf_passing
controller_manager
test_controller
ros2_control_test_assets::ros2_control_test_assets
)
ament_target_dependencies(test_controller_manager_urdf_passing
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,7 @@ class ControllerManager : public rclcpp::Node
std::vector<std::string> get_controller_names();
std::pair<std::string, std::string> split_command_interface(
const std::string & command_interface);
void init_controller_manager();
void subscribe_to_robot_description_topic();

/**
* Clear request lists used when switching controllers. The lists are shared between "callback"
Expand Down Expand Up @@ -546,7 +546,6 @@ class ControllerManager : public rclcpp::Node

std::string robot_description_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
rclcpp::TimerBase::SharedPtr robot_description_notification_timer_;

struct SwitchParams
{
Expand Down
80 changes: 0 additions & 80 deletions controller_manager/test/test_spawner_unspawner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ using ::testing::Return;
using namespace std::chrono_literals;
class TestLoadController : public ControllerManagerFixture<controller_manager::ControllerManager>
{
public:
void SetUp() override
{
ControllerManagerFixture::SetUp();
Expand Down Expand Up @@ -275,82 +274,3 @@ TEST_F(TestLoadController, unload_on_kill)

ASSERT_EQ(cm_->get_loaded_controllers().size(), 0ul);
}

class TestLoadControllerWithoutRobotDescription
: public ControllerManagerFixture<controller_manager::ControllerManager>
{
public:
TestLoadControllerWithoutRobotDescription()
: ControllerManagerFixture<controller_manager::ControllerManager>("")
{
}

void SetUp() override
{
ControllerManagerFixture::SetUp();

update_timer_ = cm_->create_wall_timer(
std::chrono::milliseconds(10),
[&]()
{
cm_->read(time_, PERIOD);
cm_->update(time_, PERIOD);
cm_->write(time_, PERIOD);
});

update_executor_ =
std::make_shared<rclcpp::executors::MultiThreadedExecutor>(rclcpp::ExecutorOptions(), 2);

update_executor_->add_node(cm_);
update_executor_spin_future_ =
std::async(std::launch::async, [this]() -> void { update_executor_->spin(); });

// This sleep is needed to prevent a too fast test from ending before the
// executor has began to spin, which causes it to hang
std::this_thread::sleep_for(50ms);
}

void TearDown() override { update_executor_->cancel(); }

rclcpp::TimerBase::SharedPtr robot_description_sending_timer_;

protected:
rclcpp::TimerBase::SharedPtr update_timer_;

// Using a MultiThreadedExecutor so we can call update on a separate thread from service callbacks
std::shared_ptr<rclcpp::Executor> update_executor_;
std::future<void> update_executor_spin_future_;
};

TEST_F(TestLoadControllerWithoutRobotDescription, when_no_robot_description_spawner_times_out)
{
cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME));

ControllerManagerRunner cm_runner(this);
EXPECT_EQ(call_spawner("ctrl_1 -c test_controller_manager"), 1)
<< "could not spawn controller because not robot description and not services for controller "
"manager are active";
}

TEST_F(
TestLoadControllerWithoutRobotDescription,
controller_starting_with_later_load_of_robot_description)
{
cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME));

// Delay sending robot description
robot_description_sending_timer_ = cm_->create_wall_timer(
std::chrono::milliseconds(1500), [&]() { pass_robot_description_to_cm_and_rm(); });

ControllerManagerRunner cm_runner(this);
EXPECT_EQ(call_spawner("ctrl_1 -c test_controller_manager"), 1)
<< "could not activate control because not robot description";

ASSERT_EQ(cm_->get_loaded_controllers().size(), 1ul);
{
auto ctrl_1 = cm_->get_loaded_controllers()[0];
ASSERT_EQ(ctrl_1.info.name, "ctrl_1");
ASSERT_EQ(ctrl_1.info.type, test_controller::TEST_CONTROLLER_CLASS_NAME);
ASSERT_EQ(ctrl_1.c->get_state().id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
}
}
2 changes: 1 addition & 1 deletion hardware_interface_testing/test/test_resource_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class TestableResourceManager : public hardware_interface::ResourceManager
public:
friend ResourceManagerTest;

FRIEND_TEST(ResourceManagerTest, initialization_with_urdf_manual_validation);
FRIEND_TEST(ResourceManagerTest, initialization_with_urdf_and_manual_validation);
FRIEND_TEST(ResourceManagerTest, post_initialization_add_components);
FRIEND_TEST(ResourceManagerTest, managing_controllers_reference_interfaces);
FRIEND_TEST(ResourceManagerTest, resource_availability_and_claiming_in_lifecycle);
Expand Down

0 comments on commit c1ba8bc

Please sign in to comment.