Skip to content

Commit

Permalink
Remaining controllers
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 3, 2025
1 parent d37d5b2 commit ab5de5f
Show file tree
Hide file tree
Showing 8 changed files with 38 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,11 @@ void JointGroupEffortControllerTest::SetUp()
controller_ = std::make_unique<FriendJointGroupEffortController>();
}

void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); }
void JointGroupEffortControllerTest::TearDown()
{
controller_->get_node()->shutdown();
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 @@ -46,7 +46,11 @@ void ForwardCommandControllerTest::SetUp()
controller_ = std::make_unique<FriendForwardCommandController>();
}

void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }
void ForwardCommandControllerTest::TearDown()
{
controller_->get_node()->shutdown();
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,11 @@ void MultiInterfaceForwardCommandControllerTest::SetUp()
controller_ = std::make_unique<FriendMultiInterfaceForwardCommandController>();
}

void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); }
void MultiInterfaceForwardCommandControllerTest::TearDown()
{
controller_->get_node()->shutdown();
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void MultiInterfaceForwardCommandControllerTest::SetUpController(bool set_params_and_activate)
{
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 @@ -52,7 +52,8 @@ void GripperControllerTest<T>::SetUp()
template <typename T>
void GripperControllerTest<T>::TearDown()
{
controller_.reset(nullptr);
controller_->get_node()->shutdown();
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

template <typename T>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,11 @@ void GripperControllerTest::SetUp()
controller_ = std::make_unique<FriendGripperController>();
}

void GripperControllerTest::TearDown() { controller_.reset(nullptr); }
void GripperControllerTest::TearDown()
{
controller_->get_node()->shutdown();
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
8 changes: 6 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,13 @@ class PidControllerFixture : public ::testing::Test
"/test_pid_controller/set_feedforward_control");
}

static void TearDownTestCase() { rclcpp::shutdown(); }
void TearDown()
{
controller_->get_node()->shutdown();
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
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,11 @@ void JointGroupPositionControllerTest::SetUp()
controller_ = std::make_unique<FriendJointGroupPositionController>();
}

void JointGroupPositionControllerTest::TearDown() { controller_.reset(nullptr); }
void JointGroupPositionControllerTest::TearDown()
{
controller_->get_node()->shutdown();
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void JointGroupPositionControllerTest::SetUpController()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,11 @@ void JointGroupVelocityControllerTest::SetUp()
controller_ = std::make_unique<FriendJointGroupVelocityController>();
}

void JointGroupVelocityControllerTest::TearDown() { controller_.reset(nullptr); }
void JointGroupVelocityControllerTest::TearDown()
{
controller_->get_node()->shutdown();
controller_.reset(nullptr); // this calls the dtor, but does not call shutdown transition
}

void JointGroupVelocityControllerTest::SetUpController()
{
Expand Down

0 comments on commit ab5de5f

Please sign in to comment.