Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,11 @@ class ControllerLoaderPluginlib : public ControllerLoaderInterface
virtual ~ControllerLoaderPluginlib() = default;

CONTROLLER_MANAGER_PUBLIC
controller_interface::ControllerInterfaceSharedPtr create(const std::string & controller_type);
controller_interface::ControllerInterfaceSharedPtr create(const std::string & controller_type)
override;

CONTROLLER_MANAGER_PUBLIC
bool is_available(const std::string & controller_type) const;
bool is_available(const std::string & controller_type) const override;

CONTROLLER_MANAGER_PUBLIC
std::vector<std::string> get_declared_classes() const override;
Expand Down
8 changes: 5 additions & 3 deletions controller_manager/test/controller_manager_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,13 +71,15 @@ class ControllerLoaderMock : public controller_manager::ControllerLoaderInterfac
ControllerLoaderMock()
: controller_manager::ControllerLoaderInterface("controller_interface::MockControllerInterface")
{}
MOCK_METHOD1(create, controller_interface::ControllerInterfaceSharedPtr(const std::string &));
MOCK_CONST_METHOD1(is_available, bool(const std::string &));
MOCK_METHOD(
controller_interface::ControllerInterfaceSharedPtr, create, (const std::string &),
(override));
MOCK_METHOD(bool, is_available, (const std::string &), (const, override));
std::vector<std::string> get_declared_classes() const override
{
return {MOCK_TEST_CONTROLLER_NAME};
}
MOCK_METHOD0(reload, void());
MOCK_METHOD(void, reload, (), (override));
};

#endif // CONTROLLER_MANAGER_TEST_COMMON_HPP_
8 changes: 0 additions & 8 deletions controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@ using ::testing::Return;

using namespace std::chrono_literals;


class TestControllerManagerSrvs : public TestControllerManager
{
public:
Expand Down Expand Up @@ -137,7 +136,6 @@ TEST_F(TestControllerManagerSrvs, list_controller_types)
::testing::Contains("controller_interface::MockControllerInterface"));
}


TEST_F(TestControllerManagerSrvs, list_controllers_srv) {
rclcpp::executors::SingleThreadedExecutor srv_executor;
rclcpp::Node::SharedPtr srv_node = std::make_shared<rclcpp::Node>("srv_client");
Expand Down Expand Up @@ -176,7 +174,6 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv) {
result->controller.size());
ASSERT_EQ("active", result->controller[0].state);


cm_->switch_controller(
{}, {test_controller::TEST_CONTROLLER_NAME},
controller_manager_msgs::srv::SwitchController::Request::STRICT, true,
Expand Down Expand Up @@ -207,7 +204,6 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv) {
auto request =
std::make_shared<controller_manager_msgs::srv::ReloadControllerLibraries::Request>();


std::shared_ptr<ControllerLoaderMock> mock_loader(new ControllerLoaderMock);

cm_->register_controller_loader(mock_loader);
Expand All @@ -219,7 +215,6 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv) {
auto result = call_service_and_wait(*client, request, srv_executor);
ASSERT_TRUE(result->ok);


// Add a controller, but stopped
auto test_controller = cm_->load_controller(
test_controller::TEST_CONTROLLER_NAME,
Expand Down Expand Up @@ -257,7 +252,6 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv) {
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
test_controller->get_lifecycle_node()->get_current_state().id());


// Failed reload due to active controller
request->force_kill = false;
EXPECT_CALL(*mock_loader, reload).Times(0);
Expand All @@ -278,7 +272,6 @@ TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv) {
result = call_service_and_wait(*client, request, srv_executor, true);
ASSERT_TRUE(result->ok);


ASSERT_EQ(
test_controller.use_count(),
1) << "No more references to the controller after reloading.";
Expand Down Expand Up @@ -320,7 +313,6 @@ TEST_F(TestControllerManagerSrvs, unload_controller_srv) {
auto result = call_service_and_wait(*client, request, srv_executor);
ASSERT_FALSE(result->ok) << "Controller not loaded: " << request->name;


auto test_controller = std::make_shared<test_controller::TestController>();
auto abstract_test_controller = cm_->add_controller(
test_controller, test_controller::TEST_CONTROLLER_NAME,
Expand Down