Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix LifecycleNode in tests #1470

Closed
wants to merge 7 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -126,9 +126,20 @@ class AckermannSteeringControllerFixture : public ::testing::Test
"/test_ackermann_steering_controller/reference", rclcpp::SystemDefaultsQoS());
}

static void TearDownTestCase() {}
void TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
Comment on lines +131 to +138
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
if(controller_->get_node().get_state() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN)
{
controller_->get_node()->shutdown();
}

I think it is better to have it like this no?. trying and catching everything might hide some issues we might add in future. What's your opinion on this @christophfroehlich ?. If you think it's fine, I'm okay with it

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The following code

  if(range_broadcaster_->get_node()->get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN)
  {
    range_broadcaster_->get_node()->shutdown();
  }

still throws


2: [ RUN      ] RangeSensorBroadcasterTest.Initialize_RangeBroadcaster_Exception
2: unknown file: Failure
2: C++ exception with description "Lifecycle node hasn't been initialized yet!" thrown in TearDown().

here

https://github.com/ros-controls/ros2_control/blob/d8a21c4e5effa2ac3b75a3dffbc6b48471e18a1f/controller_interface/src/controller_interface_base.cpp#L205-L212

I don't see any other possibility with the controller_interface API.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we could only catch std::runtime_error and rethrow others.
Or we change the upstream API to check if the node is initialized or add a shutdown method, which itself checks if the node is initialized.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ahh I didn't know that this exception is in the controller interface base. If this is the case, we can add an upstream API to check if the controller is initialized or may be in the destructor of the base class, call shutdown if the node is valid and also the state makes sense. What do you think?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we never trigger the shutdown transition in the controller_manager, maybe this is a bug we should solve?
Currently we only have virtual default destructors of the ControllerInterfaceBase and ControllerInterface class, where would you add that?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would say in the destructor of the controller_interface_base. As that's the common one for both normal and chained controllers

controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void TearDown() { controller_.reset(nullptr); }
static void TearDownTestCase() {}

protected:
void SetUpController(const std::string controller_name = "test_ackermann_steering_controller")
Expand Down
16 changes: 12 additions & 4 deletions admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,13 +129,21 @@ class AdmittanceControllerTest : public ::testing::Test
test_broadcaster_node_ = std::make_shared<rclcpp::Node>("test_broadcaster_node");
}

static void TearDownTestCase()
static void TearDownTestCase() {}

void TearDown()
{
// rclcpp::shutdown();
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void TearDown() { controller_.reset(nullptr); }

protected:
controller_interface::return_type SetUpController(
const std::string & controller_name, const std::vector<rclcpp::Parameter> & parameter_overrides)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,9 +124,20 @@ class BicycleSteeringControllerFixture : public ::testing::Test
"/test_bicycle_steering_controller/reference", rclcpp::SystemDefaultsQoS());
}

static void TearDownTestCase() {}
void TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void TearDown() { controller_.reset(nullptr); }
static void TearDownTestCase() {}

protected:
void SetUpController(const std::string controller_name = "test_bicycle_steering_controller")
Expand Down
19 changes: 17 additions & 2 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,9 @@ class TestableDiffDriveController : public diff_drive_controller::DiffDriveContr
class TestDiffDriveController : public ::testing::Test
{
protected:
void SetUp() override
static void SetUpTestCase() {}

void SetUp()
{
// use the name of the test as the controller name (i.e, the node name) to be able to set
// parameters from yaml for each test
Expand All @@ -97,7 +99,20 @@ class TestDiffDriveController : public ::testing::Test
controller_name + "/cmd_vel", rclcpp::SystemDefaultsQoS());
}

static void TearDownTestCase() { rclcpp::shutdown(); }
void TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

static void TearDownTestCase() {}

/// Publish velocity msgs
/**
Expand Down
13 changes: 12 additions & 1 deletion effort_controllers/test/test_joint_group_effort_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,18 @@ void JointGroupEffortControllerTest::SetUp()
controller_ = std::make_unique<FriendJointGroupEffortController>();
}

void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); }
void JointGroupEffortControllerTest::TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void JointGroupEffortControllerTest::SetUpController()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,18 @@ void ForceTorqueSensorBroadcasterTest::SetUp()
fts_broadcaster_ = std::make_unique<FriendForceTorqueSensorBroadcaster>();
}

void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullptr); }
void ForceTorqueSensorBroadcasterTest::TearDown()
{
try
{
fts_broadcaster_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
fts_broadcaster_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,18 @@ void ForwardCommandControllerTest::SetUp()
controller_ = std::make_unique<FriendForwardCommandController>();
}

void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }
void ForwardCommandControllerTest::TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void ForwardCommandControllerTest::SetUpController()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,18 @@ void MultiInterfaceForwardCommandControllerTest::SetUp()
controller_ = std::make_unique<FriendMultiInterfaceForwardCommandController>();
}

void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }
void MultiInterfaceForwardCommandControllerTest::TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void MultiInterfaceForwardCommandControllerTest::SetUpController(bool set_params_and_activate)
{
Expand Down
10 changes: 9 additions & 1 deletion gripper_controllers/test/test_gripper_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,15 @@ void GripperControllerTest<T>::SetUp()
template <typename T>
void GripperControllerTest<T>::TearDown()
{
controller_.reset(nullptr);
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

template <typename T>
Expand Down
13 changes: 12 additions & 1 deletion imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,18 @@ void IMUSensorBroadcasterTest::SetUp()
imu_broadcaster_ = std::make_unique<FriendIMUSensorBroadcaster>();
}

void IMUSensorBroadcasterTest::TearDown() { imu_broadcaster_.reset(nullptr); }
void IMUSensorBroadcasterTest::TearDown()
{
try
{
imu_broadcaster_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
imu_broadcaster_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void IMUSensorBroadcasterTest::SetUpIMUBroadcaster()
{
Expand Down
13 changes: 12 additions & 1 deletion joint_state_broadcaster/test/test_joint_state_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,18 @@ void JointStateBroadcasterTest::SetUp()
state_broadcaster_ = std::make_unique<FriendJointStateBroadcaster>();
}

void JointStateBroadcasterTest::TearDown() { state_broadcaster_.reset(nullptr); }
void JointStateBroadcasterTest::TearDown()
{
try
{
state_broadcaster_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
state_broadcaster_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void JointStateBroadcasterTest::SetUpStateBroadcaster(
const std::vector<std::string> & joint_names, const std::vector<std::string> & interfaces)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,14 @@ class TrajectoryControllerTest : public ::testing::Test
traj_controller_->get_node()->deactivate().id(),
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
}
try
{
traj_controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
}
}

Expand Down
15 changes: 13 additions & 2 deletions mecanum_drive_controller/test/test_mecanum_drive_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,9 +155,20 @@ class MecanumDriveControllerFixture : public ::testing::Test
"/test_mecanum_drive_controller/tf_odometry", rclcpp::SystemDefaultsQoS());
}

static void TearDownTestCase() {}
void TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void TearDown() { controller_.reset(nullptr); }
static void TearDownTestCase() {}

protected:
void SetUpController(const std::string controller_name = "test_mecanum_drive_controller")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,18 @@ void GripperControllerTest::SetUp()
controller_ = std::make_unique<FriendGripperController>();
}

void GripperControllerTest::TearDown() { controller_.reset(nullptr); }
void GripperControllerTest::TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void GripperControllerTest::SetUpController(
const std::string & controller_name = "test_gripper_action_position_controller",
Expand Down
15 changes: 13 additions & 2 deletions pid_controller/test/test_pid_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,9 +128,20 @@ class PidControllerFixture : public ::testing::Test
"/test_pid_controller/set_feedforward_control");
}

static void TearDownTestCase() { rclcpp::shutdown(); }
void TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void TearDown() { controller_.reset(nullptr); }
static void TearDownTestCase() {}

protected:
void SetUpController(const std::string controller_name = "test_pid_controller")
Expand Down
13 changes: 12 additions & 1 deletion pose_broadcaster/test/test_pose_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,18 @@ using hardware_interface::LoanedStateInterface;

void PoseBroadcasterTest::SetUp() { pose_broadcaster_ = std::make_unique<PoseBroadcaster>(); }

void PoseBroadcasterTest::TearDown() { pose_broadcaster_.reset(nullptr); }
void PoseBroadcasterTest::TearDown()
{
try
{
pose_broadcaster_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
pose_broadcaster_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void PoseBroadcasterTest::SetUpPoseBroadcaster()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,18 @@ void JointGroupPositionControllerTest::SetUp()
controller_ = std::make_unique<FriendJointGroupPositionController>();
}

void JointGroupPositionControllerTest::TearDown() { controller_.reset(nullptr); }
void JointGroupPositionControllerTest::TearDown()
{
try
{
controller_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void JointGroupPositionControllerTest::SetUpController()
{
Expand Down
13 changes: 12 additions & 1 deletion range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,18 @@ void RangeSensorBroadcasterTest::SetUp()
range_broadcaster_ = std::make_unique<range_sensor_broadcaster::RangeSensorBroadcaster>();
}

void RangeSensorBroadcasterTest::TearDown() { range_broadcaster_.reset(nullptr); }
void RangeSensorBroadcasterTest::TearDown()
{
try
{
range_broadcaster_->get_node()->shutdown();
}
catch (...)
{
// ignore case where node is not initialized
}
range_broadcaster_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

controller_interface::return_type RangeSensorBroadcasterTest::init_broadcaster(
std::string broadcaster_name)
Expand Down
Loading
Loading