Skip to content

Commit

Permalink
Add namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Apr 26, 2024
1 parent 2412651 commit a38ed95
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
8 changes: 4 additions & 4 deletions imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,10 @@ void IMUSensorBroadcasterTest::SetUp()

void IMUSensorBroadcasterTest::TearDown() { imu_broadcaster_.reset(nullptr); }

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

std::vector<LoanedStateInterface> state_ifs;
Expand All @@ -78,10 +78,10 @@ void IMUSensorBroadcasterTest::subscribe_and_get_message(
sensor_msgs::msg::Imu & imu_msg, const std::string & ns)
{
// create a new subscriber
rclcpp::Node test_subscription_node("test_subscription_node");
rclcpp::Node test_subscription_node("test_subscription_node", ns);
auto subs_callback = [&](const sensor_msgs::msg::Imu::SharedPtr) {};
auto subscription = test_subscription_node.create_subscription<sensor_msgs::msg::Imu>(
"/test_imu_sensor_broadcaster/imu", 10, subs_callback);
"test_imu_sensor_broadcaster/imu", 10, subs_callback);

// call update to publish the test value
// since update doesn't guarantee a published message, republish until received
Expand Down
4 changes: 2 additions & 2 deletions imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class IMUSensorBroadcasterTest : public ::testing::Test
void SetUp();
void TearDown();

void SetUpIMUBroadcaster();
void SetUpIMUBroadcaster(const std::string & ns = "");

protected:
const std::string sensor_name_ = "imu_sensor";
Expand Down Expand Up @@ -78,7 +78,7 @@ class IMUSensorBroadcasterTest : public ::testing::Test

std::unique_ptr<FriendIMUSensorBroadcaster> imu_broadcaster_;

void subscribe_and_get_message(sensor_msgs::msg::Imu & imu_msg);
void subscribe_and_get_message(sensor_msgs::msg::Imu & imu_msg, const std::string & ns = "");
};

struct TestPrefixParams
Expand Down

0 comments on commit a38ed95

Please sign in to comment.