Skip to content

Commit

Permalink
add a new method to be able to override the NodeOptions
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Nov 15, 2023
1 parent cf405bc commit ffe5e5e
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -115,8 +115,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
virtual return_type init(
const std::string & controller_name, const std::string & urdf,
const std::string & namespace_ = "",
const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions().enable_logger_service(true));
const std::string & namespace_ = "");

/// Custom configure method to read additional parameters for controller-nodes
/*
Expand Down Expand Up @@ -159,6 +158,12 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
const std::string & get_robot_description() const;

CONTROLLER_INTERFACE_PUBLIC
virtual rclcpp::NodeOptions get_node_options() const
{
return rclcpp::NodeOptions().enable_logger_service(true);
}

/// Declare and initialize a parameter with a type.
/**
*
Expand Down
6 changes: 3 additions & 3 deletions controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,11 @@
namespace controller_interface
{
return_type ControllerInterfaceBase::init(
const std::string & controller_name, const std::string & urdf, const std::string & namespace_,
const rclcpp::NodeOptions & node_options)
const std::string & controller_name, const std::string & urdf, const std::string & namespace_)
{
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
controller_name, namespace_, node_options, false); // disable LifecycleNode service interfaces
controller_name, namespace_, get_node_options(),
false); // disable LifecycleNode service interfaces
urdf_ = urdf;

try
Expand Down

0 comments on commit ffe5e5e

Please sign in to comment.