Skip to content

Commit a9e36ac

Browse files
authored
Controller interface api update to ros2_controller packages (backport #1973) (#2068)
1 parent 4a18571 commit a9e36ac

27 files changed

Lines changed: 267 additions & 119 deletions

File tree

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -133,9 +133,13 @@ class AckermannSteeringControllerFixture : public ::testing::Test
133133
protected:
134134
void SetUpController(const std::string controller_name = "test_ackermann_steering_controller")
135135
{
136-
ASSERT_EQ(
137-
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
138-
controller_interface::return_type::OK);
136+
controller_interface::ControllerInterfaceParams params;
137+
params.controller_name = controller_name;
138+
params.robot_description = "";
139+
params.update_rate = 0;
140+
params.node_namespace = "";
141+
params.node_options = controller_->define_custom_node_options();
142+
ASSERT_EQ(controller_->init(params), controller_interface::return_type::OK);
139143

140144
if (position_feedback_ == true)
141145
{

admittance_controller/test/test_admittance_controller.hpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -160,8 +160,13 @@ class AdmittanceControllerTest : public ::testing::Test
160160
controller_interface::return_type SetUpControllerCommon(
161161
const std::string & controller_name, const rclcpp::NodeOptions & options)
162162
{
163-
auto result =
164-
controller_->init(controller_name, controller_->robot_description_, 0, "", options);
163+
controller_interface::ControllerInterfaceParams params;
164+
params.controller_name = controller_name;
165+
params.robot_description = controller_->robot_description_;
166+
params.update_rate = 0;
167+
params.node_namespace = "";
168+
params.node_options = options;
169+
auto result = controller_->init(params);
165170

166171
controller_->export_reference_interfaces();
167172
assign_interfaces();

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -131,9 +131,13 @@ class BicycleSteeringControllerFixture : public ::testing::Test
131131
protected:
132132
void SetUpController(const std::string controller_name = "test_bicycle_steering_controller")
133133
{
134-
ASSERT_EQ(
135-
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
136-
controller_interface::return_type::OK);
134+
controller_interface::ControllerInterfaceParams params;
135+
params.controller_name = controller_name;
136+
params.robot_description = "";
137+
params.update_rate = 0;
138+
params.node_namespace = "";
139+
params.node_options = controller_->define_custom_node_options();
140+
ASSERT_EQ(controller_->init(params), controller_interface::return_type::OK);
137141

138142
if (position_feedback_ == true)
139143
{

chained_filter_controller/test/test_chained_filter.cpp

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,13 @@ void ChainedFilterTest::SetUpController(
4848
auto node_options = controller_->define_custom_node_options();
4949
node_options.parameter_overrides(parameters);
5050

51-
const auto result = controller_->init(node_name, "", 0, "", node_options);
51+
controller_interface::ControllerInterfaceParams params;
52+
params.controller_name = node_name;
53+
params.robot_description = "";
54+
params.update_rate = 0;
55+
params.node_namespace = "";
56+
params.node_options = node_options;
57+
const auto result = controller_->init(params);
5258
ASSERT_EQ(result, controller_interface::return_type::OK);
5359

5460
std::vector<LoanedStateInterface> state_ifs;
@@ -61,8 +67,13 @@ TEST_F(ChainedFilterTest, InitReturnsSuccess) { SetUpController(); }
6167

6268
TEST_F(ChainedFilterTest, InitFailureWithNoParams)
6369
{
64-
const auto result = controller_->init(
65-
"test_chained_filter_no_params", "", 0, "", controller_->define_custom_node_options());
70+
controller_interface::ControllerInterfaceParams params;
71+
params.controller_name = "test_chained_filter_no_params";
72+
params.robot_description = "";
73+
params.update_rate = 0;
74+
params.node_namespace = "";
75+
params.node_options = controller_->define_custom_node_options();
76+
const auto result = controller_->init(params);
6677
EXPECT_EQ(result, controller_interface::return_type::ERROR);
6778
}
6879

chained_filter_controller/test/test_multiple_chained_filter.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,13 @@ void MultipleChainedFilterTest::SetUpController(
4848
auto node_options = controller_->define_custom_node_options();
4949
node_options.parameter_overrides(parameters);
5050

51-
const auto result = controller_->init(node_name, "", 0, "", node_options);
51+
controller_interface::ControllerInterfaceParams params;
52+
params.controller_name = node_name;
53+
params.robot_description = "";
54+
params.update_rate = 0;
55+
params.node_namespace = "";
56+
params.node_options = node_options;
57+
const auto result = controller_->init(params);
5258
ASSERT_EQ(result, controller_interface::return_type::OK);
5359

5460
std::vector<LoanedStateInterface> state_ifs;

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 14 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -206,8 +206,13 @@ class TestDiffDriveController : public ::testing::Test
206206

207207
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
208208
node_options.parameter_overrides(parameter_overrides);
209-
210-
return controller_->init(controller_name, urdf_, 0, ns, node_options);
209+
controller_interface::ControllerInterfaceParams params;
210+
params.controller_name = controller_name;
211+
params.robot_description = urdf_;
212+
params.update_rate = 0;
213+
params.node_namespace = ns;
214+
params.node_options = node_options;
215+
return controller_->init(params);
211216
}
212217

213218
std::string controller_name;
@@ -237,8 +242,13 @@ class TestDiffDriveController : public ::testing::Test
237242

238243
TEST_F(TestDiffDriveController, init_fails_without_parameters)
239244
{
240-
const auto ret =
241-
controller_->init(controller_name, urdf_, 0, "", controller_->define_custom_node_options());
245+
controller_interface::ControllerInterfaceParams params;
246+
params.controller_name = controller_name;
247+
params.robot_description = urdf_;
248+
params.update_rate = 0;
249+
params.node_namespace = "";
250+
params.node_options = controller_->define_custom_node_options();
251+
const auto ret = controller_->init(params);
242252
ASSERT_EQ(ret, controller_interface::return_type::ERROR);
243253
}
244254

effort_controllers/test/test_joint_group_effort_controller.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,13 @@ void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); }
3838

3939
void JointGroupEffortControllerTest::SetUpController()
4040
{
41-
const auto result = controller_->init(
42-
"test_joint_group_effort_controller", "", 0, "", controller_->define_custom_node_options());
41+
controller_interface::ControllerInterfaceParams params;
42+
params.controller_name = "test_joint_group_effort_controller";
43+
params.robot_description = "";
44+
params.update_rate = 0;
45+
params.node_namespace = "";
46+
params.node_options = controller_->define_custom_node_options();
47+
const auto result = controller_->init(params);
4348
ASSERT_EQ(result, controller_interface::return_type::OK);
4449

4550
std::vector<LoanedCommandInterface> command_ifs;

force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,13 @@ void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullp
5454

5555
void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster(std::string node_name)
5656
{
57-
const auto result =
58-
fts_broadcaster_->init(node_name, "", 0, "", fts_broadcaster_->define_custom_node_options());
57+
controller_interface::ControllerInterfaceParams params;
58+
params.controller_name = node_name;
59+
params.robot_description = "";
60+
params.update_rate = 0;
61+
params.node_namespace = "";
62+
params.node_options = fts_broadcaster_->define_custom_node_options();
63+
const auto result = fts_broadcaster_->init(params);
5964
ASSERT_EQ(result, controller_interface::return_type::OK);
6065

6166
std::vector<LoanedStateInterface> state_ifs;

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,13 @@ void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }
5151

5252
void ForwardCommandControllerTest::SetUpController()
5353
{
54-
const auto result = controller_->init(
55-
"forward_command_controller", "", 0, "", controller_->define_custom_node_options());
54+
controller_interface::ControllerInterfaceParams params;
55+
params.controller_name = "forward_command_controller";
56+
params.robot_description = "";
57+
params.update_rate = 0;
58+
params.node_namespace = "";
59+
params.node_options = controller_->define_custom_node_options();
60+
const auto result = controller_->init(params);
5661
ASSERT_EQ(result, controller_interface::return_type::OK);
5762

5863
std::vector<LoanedCommandInterface> command_ifs;

forward_command_controller/test/test_multi_interface_forward_command_controller.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -53,9 +53,13 @@ void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset(
5353

5454
void MultiInterfaceForwardCommandControllerTest::SetUpController(bool set_params_and_activate)
5555
{
56-
const auto result = controller_->init(
57-
"multi_interface_forward_command_controller", "", 0, "",
58-
controller_->define_custom_node_options());
56+
controller_interface::ControllerInterfaceParams params;
57+
params.controller_name = "multi_interface_forward_command_controller";
58+
params.robot_description = "";
59+
params.update_rate = 0;
60+
params.node_namespace = "";
61+
params.node_options = controller_->define_custom_node_options();
62+
const auto result = controller_->init(params);
5963
ASSERT_EQ(result, controller_interface::return_type::OK);
6064

6165
std::vector<LoanedCommandInterface> command_ifs;

0 commit comments

Comments
 (0)