From 56c1ef6e6c41c3c9210998e24d1fc5028f334fed Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota <sai.kishor@pal-robotics.com> Date: Sun, 22 Oct 2023 11:49:30 +0200 Subject: [PATCH] fix code formatting --- .../controller_interface/controller_interface_base.hpp | 5 +++-- controller_interface/src/controller_interface_base.cpp | 4 ++-- .../test_controller_failed_init.cpp | 2 +- 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index ca5ab5e57b..bba334aa3c 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -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 /* diff --git a/controller_interface/src/controller_interface_base.cpp b/controller_interface/src/controller_interface_base.cpp index 2586083d5b..c30d264b90 100644 --- a/controller_interface/src/controller_interface_base.cpp +++ b/controller_interface/src/controller_interface_base.cpp @@ -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 diff --git a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp index 2c3d58e7fd..ba762573c7 100644 --- a/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp +++ b/controller_manager/test/test_controller_failed_init/test_controller_failed_init.cpp @@ -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;