Skip to content

Commit 2817f27

Browse files
authored
Fix tests for using new get_node_options API (#840)
1 parent fd8b91f commit 2817f27

File tree

19 files changed

+52
-19
lines changed

19 files changed

+52
-19
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,9 @@ class AckermannSteeringControllerFixture : public ::testing::Test
147147
protected:
148148
void SetUpController(const std::string controller_name = "test_ackermann_steering_controller")
149149
{
150-
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
150+
ASSERT_EQ(
151+
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
152+
controller_interface::return_type::OK);
151153

152154
if (position_feedback_ == true)
153155
{

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,9 @@ class BicycleSteeringControllerFixture : public ::testing::Test
144144
protected:
145145
void SetUpController(const std::string controller_name = "test_bicycle_steering_controller")
146146
{
147-
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
147+
ASSERT_EQ(
148+
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
149+
controller_interface::return_type::OK);
148150

149151
if (position_feedback_ == true)
150152
{

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -218,7 +218,8 @@ class TestDiffDriveController : public ::testing::Test
218218

219219
TEST_F(TestDiffDriveController, init_fails_without_parameters)
220220
{
221-
const auto ret = controller_->init(controller_name, urdf_, 0);
221+
const auto ret =
222+
controller_->init(controller_name, urdf_, 0, "", controller_->define_custom_node_options());
222223
ASSERT_EQ(ret, controller_interface::return_type::ERROR);
223224
}
224225

doc/writing_new_controller.rst

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,9 @@ The following is a step-by-step guide to create source files, basic tests, and c
4242
5. Add a constructor without parameters and the following public methods overriding the ``ControllerInterface`` definition: ``on_init``, ``command_interface_configuration``, ``state_interface_configuration``, ``on_configure``, ``on_activate``, ``on_deactivate``, ``update``.
4343
For exact definitions check the ``controller_interface/controller_interface.hpp`` header or one of the controllers from `ros2_controllers <https://github.com/ros-controls/ros2_controllers>`_.
4444

45-
6. (optional) Often, controllers accept lists of joint names and interface names as parameters.
45+
6. (Optional) The NodeOptions of the LifecycleNode can be personalized by overriding the default method ``get_node_options``.
46+
47+
7. (Optional) Often, controllers accept lists of joint names and interface names as parameters.
4648
If so, you can add two protected string vectors to store those values.
4749

4850
4. **Adding definitions into source file (.cpp)**

effort_controllers/test/test_joint_group_effort_controller.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,8 @@ void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); }
5454

5555
void JointGroupEffortControllerTest::SetUpController()
5656
{
57-
const auto result = controller_->init("test_joint_group_effort_controller", "", 0);
57+
const auto result = controller_->init(
58+
"test_joint_group_effort_controller", "", 0, "", controller_->define_custom_node_options());
5859
ASSERT_EQ(result, controller_interface::return_type::OK);
5960

6061
std::vector<LoanedCommandInterface> command_ifs;

force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,9 @@ void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullp
5555

5656
void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
5757
{
58-
const auto result = fts_broadcaster_->init("test_force_torque_sensor_broadcaster", "", 0);
58+
const auto result = fts_broadcaster_->init(
59+
"test_force_torque_sensor_broadcaster", "", 0, "",
60+
fts_broadcaster_->define_custom_node_options());
5961
ASSERT_EQ(result, controller_interface::return_type::OK);
6062

6163
std::vector<LoanedStateInterface> state_ifs;

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,8 @@ void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }
6262

6363
void ForwardCommandControllerTest::SetUpController()
6464
{
65-
const auto result = controller_->init("forward_command_controller", "", 0);
65+
const auto result = controller_->init(
66+
"forward_command_controller", "", 0, "", controller_->define_custom_node_options());
6667
ASSERT_EQ(result, controller_interface::return_type::OK);
6768

6869
std::vector<LoanedCommandInterface> command_ifs;

forward_command_controller/test/test_multi_interface_forward_command_controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,9 @@ void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset(
6464

6565
void MultiInterfaceForwardCommandControllerTest::SetUpController(bool set_params_and_activate)
6666
{
67-
const auto result = controller_->init("multi_interface_forward_command_controller", "", 0);
67+
const auto result = controller_->init(
68+
"multi_interface_forward_command_controller", "", 0, "",
69+
controller_->define_custom_node_options());
6870
ASSERT_EQ(result, controller_interface::return_type::OK);
6971

7072
std::vector<LoanedCommandInterface> command_ifs;

gripper_controllers/test/test_gripper_controllers.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,8 @@ void GripperControllerTest<T>::TearDown()
6262
template <typename T>
6363
void GripperControllerTest<T>::SetUpController()
6464
{
65-
const auto result = controller_->init("gripper_controller", "", 0);
65+
const auto result =
66+
controller_->init("gripper_controller", "", 0, "", controller_->define_custom_node_options());
6667
ASSERT_EQ(result, controller_interface::return_type::OK);
6768

6869
std::vector<LoanedCommandInterface> command_ifs;

imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,8 @@ void IMUSensorBroadcasterTest::TearDown() { imu_broadcaster_.reset(nullptr); }
5555

5656
void IMUSensorBroadcasterTest::SetUpIMUBroadcaster()
5757
{
58-
const auto result = imu_broadcaster_->init("test_imu_sensor_broadcaster", "", 0);
58+
const auto result = imu_broadcaster_->init(
59+
"test_imu_sensor_broadcaster", "", 0, "", imu_broadcaster_->define_custom_node_options());
5960
ASSERT_EQ(result, controller_interface::return_type::OK);
6061

6162
std::vector<LoanedStateInterface> state_ifs;

0 commit comments

Comments
 (0)