Skip to content

Commit

Permalink
Broadcasters
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 3, 2025
1 parent ab5de5f commit 0562e19
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,11 @@ void ForceTorqueSensorBroadcasterTest::SetUp()
fts_broadcaster_ = std::make_unique<FriendForceTorqueSensorBroadcaster>();
}

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

void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
{
Expand Down
6 changes: 5 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,11 @@ void IMUSensorBroadcasterTest::SetUp()
imu_broadcaster_ = std::make_unique<FriendIMUSensorBroadcaster>();
}

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

void IMUSensorBroadcasterTest::SetUpIMUBroadcaster()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,11 @@ void JointStateBroadcasterTest::SetUp()
state_broadcaster_ = std::make_unique<FriendJointStateBroadcaster>();
}

void JointStateBroadcasterTest::TearDown() { state_broadcaster_.reset(nullptr); }
void JointStateBroadcasterTest::TearDown()
{
state_broadcaster_->get_node()->shutdown();
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
6 changes: 5 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,11 @@ using hardware_interface::LoanedStateInterface;

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

void PoseBroadcasterTest::TearDown() { pose_broadcaster_.reset(nullptr); }
void PoseBroadcasterTest::TearDown()
{
pose_broadcaster_->get_node()->shutdown();
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 @@ -33,7 +33,11 @@ void RangeSensorBroadcasterTest::SetUp()
range_broadcaster_ = std::make_unique<range_sensor_broadcaster::RangeSensorBroadcaster>();
}

void RangeSensorBroadcasterTest::TearDown() { range_broadcaster_.reset(nullptr); }
void RangeSensorBroadcasterTest::TearDown()
{
range_broadcaster_->get_node()->shutdown();
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

0 comments on commit 0562e19

Please sign in to comment.