Skip to content

Commit 6560606

Browse files
ct2034roncapat
andauthored
Support custom rclcpp::NodeOptions (#417) (#423)
* Support custom `rclcpp::NodeOptions` This eases static composition of multiple ROS 2 nodes * Fix * Update aggregator.hpp (cherry picked from commit 53555cf) Co-authored-by: Patrick Roncagliolo <[email protected]>
1 parent 678f8f3 commit 6560606

File tree

2 files changed

+11
-1
lines changed

2 files changed

+11
-1
lines changed

diagnostic_aggregator/include/diagnostic_aggregator/aggregator.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,13 @@ class Aggregator
111111
DIAGNOSTIC_AGGREGATOR_PUBLIC
112112
Aggregator();
113113

114+
/*!
115+
*\brief Constructor initializes with main prefix (ex: '/Robot') and custom node options
116+
*/
117+
DIAGNOSTIC_AGGREGATOR_PUBLIC
118+
explicit Aggregator(rclcpp::NodeOptions options);
119+
120+
114121
DIAGNOSTIC_AGGREGATOR_PUBLIC
115122
virtual ~Aggregator();
116123

diagnostic_aggregator/src/aggregator.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,9 +57,12 @@ using diagnostic_msgs::msg::DiagnosticStatus;
5757
* @todo(anordman): make aggregator a lifecycle node.
5858
*/
5959
Aggregator::Aggregator()
60+
: Aggregator(rclcpp::NodeOptions()) {}
61+
62+
Aggregator::Aggregator(rclcpp::NodeOptions options)
6063
: n_(std::make_shared<rclcpp::Node>(
6164
"analyzers", "",
62-
rclcpp::NodeOptions().allow_undeclared_parameters(true).
65+
options.allow_undeclared_parameters(true).
6366
automatically_declare_parameters_from_overrides(true))),
6467
logger_(rclcpp::get_logger("Aggregator")),
6568
pub_rate_(1.0),

0 commit comments

Comments
 (0)