Skip to content

Commit

Permalink
fix code formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Oct 22, 2023
1 parent 1271a92 commit 56c1ef6
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -114,8 +114,9 @@ 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 & controller_name, const std::string & urdf,
const std::string & namespace_ = "",
const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions().enable_logger_service(true));

/// Custom configure method to read additional parameters for controller-nodes
/*
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@
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_,
const rclcpp::NodeOptions & node_options)
{
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
controller_name, namespace_, node_options, false); // disable LifecycleNode service interfaces
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ TestControllerFailedInit::on_init()
}

controller_interface::return_type TestControllerFailedInit::init(
const std::string & /* controller_name */, const std::string & /* urdf */,
const std::string & /* controller_name */, const std::string & /* urdf */,
const std::string & /*namespace_*/, const rclcpp::NodeOptions & /*node_options*/)
{
return controller_interface::return_type::ERROR;
Expand Down

0 comments on commit 56c1ef6

Please sign in to comment.