@@ -48,20 +48,25 @@ class MockControllersManagerService final : public rclcpp::Node
48
48
MockControllersManagerService () : Node(" list_controllers_service" )
49
49
{
50
50
list_controller_service_ = create_service<controller_manager_msgs::srv::ListControllers>(
51
- " controller_manager/list_controllers" , std::bind (&MockControllersManagerService::handle_list_controllers_service,
52
- this , std::placeholders::_1, std::placeholders::_2));
51
+ " controller_manager/list_controllers" ,
52
+ [this ](const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request>& request,
53
+ const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& response) {
54
+ handleListControllersService (request, response);
55
+ });
53
56
switch_controller_service_ = create_service<controller_manager_msgs::srv::SwitchController>(
54
57
" controller_manager/switch_controller" ,
55
- std::bind (&MockControllersManagerService::handle_switch_controller_service, this , std::placeholders::_1,
56
- std::placeholders::_2));
58
+ [this ](const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request>& request,
59
+ const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response>& response) {
60
+ handleSwitchControllerService (request, response);
61
+ });
57
62
}
58
63
59
64
controller_manager_msgs::srv::SwitchController::Request last_request;
60
65
61
66
private:
62
- void handle_list_controllers_service (
63
- const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> /* request*/ ,
64
- std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response)
67
+ void handleListControllersService (
68
+ const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request>& /* request*/ ,
69
+ const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& response)
65
70
{
66
71
controller_manager_msgs::msg::ChainConnection chain_connection_a;
67
72
chain_connection_a.name = " B" ;
@@ -84,9 +89,9 @@ class MockControllersManagerService final : public rclcpp::Node
84
89
response->controller = { controller_a, controller_b };
85
90
}
86
91
87
- void handle_switch_controller_service (
88
- const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
89
- std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response)
92
+ void handleSwitchControllerService (
93
+ const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request>& request,
94
+ const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response>& response)
90
95
{
91
96
last_request = *request;
92
97
for (const auto & deactivate : request->deactivate_controllers )
0 commit comments