Skip to content
Merged
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 @@ -44,7 +44,9 @@ class PublisherManager
const std::string & topic_name, std::shared_ptr<T> message, size_t expected_messages = 0)
{
auto node_name = std::string("publisher") + std::to_string(counter_++);
auto publisher_node = std::make_shared<rclcpp::Node>(node_name);
auto publisher_node = std::make_shared<rclcpp::Node>(
node_name,
rclcpp::NodeOptions().start_parameter_event_publisher(false));
auto publisher = publisher_node->create_publisher<T>(topic_name, 10);

publisher_nodes_.push_back(publisher_node);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,10 @@ class SubscriptionManager
public:
SubscriptionManager()
{
subscriber_node_ = std::make_shared<rclcpp::Node>("subscriber_node");
subscriber_node_ = std::make_shared<rclcpp::Node>(
"subscriber_node",
rclcpp::NodeOptions().start_parameter_event_publisher(false)
);
}

template<typename MessageT>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@ TEST_F(RecordIntegrationTestFixture, record_all_without_discovery_ignores_later_
auto string_message = get_messages_strings()[0];
string_message->string_value = "Hello World";

auto publisher_node = std::make_shared<rclcpp::Node>("publisher_for_test");
auto publisher_node = std::make_shared<rclcpp::Node>(
"publisher_for_test",
rclcpp::NodeOptions().start_parameter_event_publisher(false));

start_recording({true, true, {}, "rmw_format", 1ms});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,9 @@ class RosBag2NodeFixture : public Test
RosBag2NodeFixture()
{
node_ = std::make_shared<rosbag2_transport::Rosbag2Node>("rosbag2");
publisher_node_ = std::make_shared<rclcpp::Node>("publisher_node");
publisher_node_ = std::make_shared<rclcpp::Node>(
"publisher_node",
rclcpp::NodeOptions().start_parameter_event_publisher(false));
}

static void SetUpTestCase()
Expand Down