Skip to content

Commit

Permalink
fix tests for API break of passing controller manager update rate in …
Browse files Browse the repository at this point in the history
…init method (#854)
  • Loading branch information
saikishor authored Nov 20, 2023
1 parent d9a6bb4 commit 6d4fb2d
Show file tree
Hide file tree
Showing 18 changed files with 40 additions and 40 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_ackermann_steering_controller")
{
ASSERT_EQ(controller_->init(controller_name, ""), controller_interface::return_type::OK);
ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK);

if (position_feedback_ == true)
{
Expand Down
2 changes: 1 addition & 1 deletion admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ class AdmittanceControllerTest : public ::testing::Test
controller_interface::return_type SetUpControllerCommon(
const std::string & controller_name, const rclcpp::NodeOptions & options)
{
auto result = controller_->init(controller_name, "", "", options);
auto result = controller_->init(controller_name, "", 0, "", options);

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

if (position_feedback_ == true)
{
Expand Down
34 changes: 17 additions & 17 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,15 +195,15 @@ class TestDiffDriveController : public ::testing::Test

TEST_F(TestDiffDriveController, configure_fails_without_parameters)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}

TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_side_defined)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -223,7 +223,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_sid

TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -239,7 +239,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size

TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -259,7 +259,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)

TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_namespace)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

std::string odom_id = "odom";
Expand Down Expand Up @@ -292,7 +292,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_names

TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_no_namespace)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

std::string odom_id = "odom";
Expand Down Expand Up @@ -327,7 +327,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_no_namesp

TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_no_namespace)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

std::string odom_id = "odom";
Expand Down Expand Up @@ -363,7 +363,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_set_name
{
std::string test_namespace = "/test_namespace";

const auto ret = controller_->init(controller_name, urdf_, test_namespace);
const auto ret = controller_->init(controller_name, urdf_, 0, test_namespace);
ASSERT_EQ(ret, controller_interface::return_type::OK);

std::string odom_id = "odom";
Expand Down Expand Up @@ -398,7 +398,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_set_names
{
std::string test_namespace = "/test_namespace";

const auto ret = controller_->init(controller_name, urdf_, test_namespace);
const auto ret = controller_->init(controller_name, urdf_, 0, test_namespace);
ASSERT_EQ(ret, controller_interface::return_type::OK);

std::string odom_id = "odom";
Expand Down Expand Up @@ -435,7 +435,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_set_name
{
std::string test_namespace = "/test_namespace";

const auto ret = controller_->init(controller_name, urdf_, test_namespace);
const auto ret = controller_->init(controller_name, urdf_, 0, test_namespace);
ASSERT_EQ(ret, controller_interface::return_type::OK);

std::string odom_id = "odom";
Expand Down Expand Up @@ -469,7 +469,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_set_name

TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -483,7 +483,7 @@ TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)

TEST_F(TestDiffDriveController, activate_succeeds_with_pos_resources_assigned)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

// We implicitly test that by default position feedback is required
Expand All @@ -499,7 +499,7 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_pos_resources_assigned)

TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -516,7 +516,7 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)

TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -533,7 +533,7 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1)

TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -550,7 +550,7 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)

TEST_F(TestDiffDriveController, cleanup)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand Down Expand Up @@ -599,7 +599,7 @@ TEST_F(TestDiffDriveController, cleanup)

TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); }

void JointGroupEffortControllerTest::SetUpController()
{
const auto result = controller_->init("test_joint_group_effort_controller", "");
const auto result = controller_->init("test_joint_group_effort_controller", "", 0);
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 @@ -53,7 +53,7 @@ void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullp

void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
{
const auto result = fts_broadcaster_->init("test_force_torque_sensor_broadcaster", "");
const auto result = fts_broadcaster_->init("test_force_torque_sensor_broadcaster", "", 0);
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 @@ -60,7 +60,7 @@ void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }

void ForwardCommandControllerTest::SetUpController()
{
const auto result = controller_->init("forward_command_controller", "");
const auto result = controller_->init("forward_command_controller", "", 0);
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 @@ -62,7 +62,7 @@ void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset(

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

std::vector<LoanedCommandInterface> command_ifs;
Expand Down
2 changes: 1 addition & 1 deletion gripper_controllers/test/test_gripper_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void GripperControllerTest<T>::TearDown()
template <typename T>
void GripperControllerTest<T>::SetUpController()
{
const auto result = controller_->init("gripper_controller", "");
const auto result = controller_->init("gripper_controller", "", 0);
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 @@ -53,7 +53,7 @@ void IMUSensorBroadcasterTest::TearDown() { imu_broadcaster_.reset(nullptr); }

void IMUSensorBroadcasterTest::SetUpIMUBroadcaster()
{
const auto result = imu_broadcaster_->init("test_imu_sensor_broadcaster", "");
const auto result = imu_broadcaster_->init("test_imu_sensor_broadcaster", "", 0);
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,7 @@ 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", "");
const auto result = state_broadcaster_->init("joint_state_broadcaster", "", 0);
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 @@ -196,7 +196,7 @@ class TrajectoryControllerTest : public ::testing::Test
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
node_options.parameter_overrides(parameter_overrides);

auto ret = traj_controller_->init(controller_name_, "", "", node_options);
auto ret = traj_controller_->init(controller_name_, "", 0, "", node_options);
if (ret != controller_interface::return_type::OK)
{
FAIL();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void JointGroupPositionControllerTest::TearDown() { controller_.reset(nullptr);

void JointGroupPositionControllerTest::SetUpController()
{
const auto result = controller_->init("test_joint_group_position_controller", "");
const auto result = controller_->init("test_joint_group_position_controller", "", 0);
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 @@ -34,7 +34,7 @@ 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, "");
result = range_broadcaster_->init(broadcaster_name, "", 0);

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

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

TEST_F(TestTricycleController, configure_fails_without_parameters)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}

TEST_F(TestTricycleController, configure_fails_if_only_traction_or_steering_side_defined)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -200,7 +200,7 @@ TEST_F(TestTricycleController, configure_fails_if_only_traction_or_steering_side

TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -213,7 +213,7 @@ TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified)

TEST_F(TestTricycleController, activate_fails_without_resources_assigned)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand All @@ -227,7 +227,7 @@ TEST_F(TestTricycleController, activate_fails_without_resources_assigned)

TEST_F(TestTricycleController, activate_succeeds_with_resources_assigned)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

// We implicitly test that by default position feedback is required
Expand All @@ -243,7 +243,7 @@ TEST_F(TestTricycleController, activate_succeeds_with_resources_assigned)

TEST_F(TestTricycleController, cleanup)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand Down Expand Up @@ -292,7 +292,7 @@ TEST_F(TestTricycleController, cleanup)

TEST_F(TestTricycleController, correct_initialization_using_parameters)
{
const auto ret = controller_->init(controller_name, urdf_);
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ class TricycleSteeringControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_tricycle_steering_controller")
{
ASSERT_EQ(controller_->init(controller_name, ""), controller_interface::return_type::OK);
ASSERT_EQ(controller_->init(controller_name, "", 0), 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,7 @@ void JointGroupVelocityControllerTest::TearDown() { controller_.reset(nullptr);

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

std::vector<LoanedCommandInterface> command_ifs;
Expand Down

0 comments on commit 6d4fb2d

Please sign in to comment.