Skip to content

Commit

Permalink
Fix tests for using new get_node_options API (#840)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Feb 1, 2024
1 parent fd8b91f commit 2817f27
Show file tree
Hide file tree
Showing 19 changed files with 52 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,9 @@ class AckermannSteeringControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_ackermann_steering_controller")
{
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
ASSERT_EQ(
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
controller_interface::return_type::OK);

if (position_feedback_ == true)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,9 @@ class BicycleSteeringControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_bicycle_steering_controller")
{
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
ASSERT_EQ(
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
controller_interface::return_type::OK);

if (position_feedback_ == true)
{
Expand Down
3 changes: 2 additions & 1 deletion diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,8 @@ class TestDiffDriveController : public ::testing::Test

TEST_F(TestDiffDriveController, init_fails_without_parameters)
{
const auto ret = controller_->init(controller_name, urdf_, 0);
const auto ret =
controller_->init(controller_name, urdf_, 0, "", controller_->define_custom_node_options());
ASSERT_EQ(ret, controller_interface::return_type::ERROR);
}

Expand Down
4 changes: 3 additions & 1 deletion doc/writing_new_controller.rst
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,9 @@ The following is a step-by-step guide to create source files, basic tests, and c
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``.
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>`_.

6. (optional) Often, controllers accept lists of joint names and interface names as parameters.
6. (Optional) The NodeOptions of the LifecycleNode can be personalized by overriding the default method ``get_node_options``.

7. (Optional) Often, controllers accept lists of joint names and interface names as parameters.
If so, you can add two protected string vectors to store those values.

4. **Adding definitions into source file (.cpp)**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,8 @@ void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); }

void JointGroupEffortControllerTest::SetUpController()
{
const auto result = controller_->init("test_joint_group_effort_controller", "", 0);
const auto result = controller_->init(
"test_joint_group_effort_controller", "", 0, "", controller_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedCommandInterface> command_ifs;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,9 @@ void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullp

void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
{
const auto result = fts_broadcaster_->init("test_force_torque_sensor_broadcaster", "", 0);
const auto result = fts_broadcaster_->init(
"test_force_torque_sensor_broadcaster", "", 0, "",
fts_broadcaster_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedStateInterface> state_ifs;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }

void ForwardCommandControllerTest::SetUpController()
{
const auto result = controller_->init("forward_command_controller", "", 0);
const auto result = controller_->init(
"forward_command_controller", "", 0, "", controller_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedCommandInterface> command_ifs;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,9 @@ void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset(

void MultiInterfaceForwardCommandControllerTest::SetUpController(bool set_params_and_activate)
{
const auto result = controller_->init("multi_interface_forward_command_controller", "", 0);
const auto result = controller_->init(
"multi_interface_forward_command_controller", "", 0, "",
controller_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedCommandInterface> command_ifs;
Expand Down
3 changes: 2 additions & 1 deletion gripper_controllers/test/test_gripper_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ void GripperControllerTest<T>::TearDown()
template <typename T>
void GripperControllerTest<T>::SetUpController()
{
const auto result = controller_->init("gripper_controller", "", 0);
const auto result =
controller_->init("gripper_controller", "", 0, "", controller_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedCommandInterface> command_ifs;
Expand Down
3 changes: 2 additions & 1 deletion imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ void IMUSensorBroadcasterTest::TearDown() { imu_broadcaster_.reset(nullptr); }

void IMUSensorBroadcasterTest::SetUpIMUBroadcaster()
{
const auto result = imu_broadcaster_->init("test_imu_sensor_broadcaster", "", 0);
const auto result = imu_broadcaster_->init(
"test_imu_sensor_broadcaster", "", 0, "", imu_broadcaster_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedStateInterface> state_ifs;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,8 @@ void JointStateBroadcasterTest::SetUpStateBroadcaster(
void JointStateBroadcasterTest::init_broadcaster_and_set_parameters(
const std::vector<std::string> & joint_names, const std::vector<std::string> & interfaces)
{
const auto result = state_broadcaster_->init("joint_state_broadcaster", "", 0);
const auto result = state_broadcaster_->init(
"joint_state_broadcaster", "", 0, "", state_broadcaster_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

state_broadcaster_->get_node()->set_parameter({"joints", joint_names});
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ class TestableJointTrajectoryController
return ret;
}

rclcpp::NodeOptions define_custom_node_options() const override { return node_options_; }

/**
* @brief wait_for_trajectory block until a new JointTrajectory is received.
* Requires that the executor is not spinned elsewhere between the
Expand Down Expand Up @@ -157,6 +159,8 @@ class TestableJointTrajectoryController

double get_cmd_timeout() { return cmd_timeout_; }

void set_node_options(const rclcpp::NodeOptions & node_options) { node_options_ = node_options; }

trajectory_msgs::msg::JointTrajectoryPoint get_state_feedback() { return state_current_; }
trajectory_msgs::msg::JointTrajectoryPoint get_state_reference() { return state_desired_; }
trajectory_msgs::msg::JointTrajectoryPoint get_state_error() { return state_error_; }
Expand All @@ -179,6 +183,7 @@ class TestableJointTrajectoryController
}

rclcpp::WaitSet joint_cmd_sub_wait_set_;
rclcpp::NodeOptions node_options_;
};

class TrajectoryControllerTest : public ::testing::Test
Expand Down Expand Up @@ -233,8 +238,10 @@ class TrajectoryControllerTest : public ::testing::Test
parameter_overrides.push_back(rclcpp::Parameter("state_interfaces", state_interface_types_));
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
node_options.parameter_overrides(parameter_overrides);
traj_controller_->set_node_options(node_options);

return traj_controller_->init(controller_name_, "", 0, "", node_options);
return traj_controller_->init(
controller_name_, "", 0, "", traj_controller_->define_custom_node_options());
}

void SetPidParameters(
Expand Down
4 changes: 3 additions & 1 deletion pid_controller/test/test_pid_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,9 @@ class PidControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_pid_controller")
{
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
ASSERT_EQ(
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
controller_interface::return_type::OK);

std::vector<hardware_interface::LoanedCommandInterface> command_ifs;
command_itfs_.reserve(dof_names_.size());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,8 @@ void JointGroupPositionControllerTest::TearDown() { controller_.reset(nullptr);

void JointGroupPositionControllerTest::SetUpController()
{
const auto result = controller_->init("test_joint_group_position_controller", "", 0);
const auto result = controller_->init(
"test_joint_group_position_controller", "", 0, "", controller_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedCommandInterface> command_ifs;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ controller_interface::return_type RangeSensorBroadcasterTest::init_broadcaster(
std::string broadcaster_name)
{
controller_interface::return_type result = controller_interface::return_type::ERROR;
result = range_broadcaster_->init(broadcaster_name, "", 0);
result = range_broadcaster_->init(
broadcaster_name, "", 0, "", range_broadcaster_->define_custom_node_options());

if (controller_interface::return_type::OK == result)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,9 @@ class SteeringControllersLibraryFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_steering_controllers_library")
{
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
ASSERT_EQ(
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
controller_interface::return_type::OK);

if (position_feedback_ == true)
{
Expand Down
3 changes: 2 additions & 1 deletion tricycle_controller/test/test_tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,8 @@ class TestTricycleController : public ::testing::Test

TEST_F(TestTricycleController, init_fails_without_parameters)
{
const auto ret = controller_->init(controller_name, urdf_, 0);
const auto ret =
controller_->init(controller_name, urdf_, 0, "", controller_->define_custom_node_options());
ASSERT_EQ(ret, controller_interface::return_type::ERROR);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,9 @@ class TricycleSteeringControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_tricycle_steering_controller")
{
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);
ASSERT_EQ(
controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()),
controller_interface::return_type::OK);

if (position_feedback_ == true)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,8 @@ void JointGroupVelocityControllerTest::TearDown() { controller_.reset(nullptr);

void JointGroupVelocityControllerTest::SetUpController()
{
const auto result = controller_->init("test_joint_group_velocity_controller", "", 0);
const auto result = controller_->init(
"test_joint_group_velocity_controller", "", 0, "", controller_->define_custom_node_options());
ASSERT_EQ(result, controller_interface::return_type::OK);

std::vector<LoanedCommandInterface> command_ifs;
Expand Down

0 comments on commit 2817f27

Please sign in to comment.