Skip to content

Commit

Permalink
Support custom rclcpp::NodeOptions (#417)
Browse files Browse the repository at this point in the history
* Support custom `rclcpp::NodeOptions`

This eases static composition of multiple ROS 2 nodes

* Fix

* Update aggregator.hpp
  • Loading branch information
roncapat authored Jan 7, 2025
1 parent cca0f14 commit 53555cf
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,13 @@ class Aggregator
DIAGNOSTIC_AGGREGATOR_PUBLIC
Aggregator();

/*!
*\brief Constructor initializes with main prefix (ex: '/Robot') and custom node options
*/
DIAGNOSTIC_AGGREGATOR_PUBLIC
explicit Aggregator(rclcpp::NodeOptions options);


DIAGNOSTIC_AGGREGATOR_PUBLIC
virtual ~Aggregator();

Expand Down
5 changes: 4 additions & 1 deletion diagnostic_aggregator/src/aggregator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,9 +57,12 @@ using diagnostic_msgs::msg::DiagnosticStatus;
* @todo(anordman): make aggregator a lifecycle node.
*/
Aggregator::Aggregator()
: Aggregator(rclcpp::NodeOptions()) {}

Aggregator::Aggregator(rclcpp::NodeOptions options)
: n_(std::make_shared<rclcpp::Node>(
"analyzers", "",
rclcpp::NodeOptions().allow_undeclared_parameters(true).
options.allow_undeclared_parameters(true).
automatically_declare_parameters_from_overrides(true))),
logger_(rclcpp::get_logger("Aggregator")),
pub_rate_(1.0),
Expand Down

0 comments on commit 53555cf

Please sign in to comment.