diff --git a/example_11/hardware/carlikebot_system.cpp b/example_11/hardware/carlikebot_system.cpp index 3c3e6aab4..f9e9343ef 100644 --- a/example_11/hardware/carlikebot_system.cpp +++ b/example_11/hardware/carlikebot_system.cpp @@ -146,14 +146,10 @@ hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_init( // // END: This part here is for exemplary purposes - Please do not copy to your production code // joint name, state, command - hw_interfaces_.resize(4, std::make_tuple( - std::string(), - std::numeric_limits::quiet_NaN(), - std::numeric_limits::quiet_NaN() - ) - ); - - + hw_interfaces_.resize( + 4, std::make_tuple( + std::string(), std::numeric_limits::quiet_NaN(), + std::numeric_limits::quiet_NaN())); // hw_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); // hw_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN()); @@ -165,7 +161,6 @@ hardware_interface::CallbackReturn CarlikeBotSystemHardware::on_init( // hw_position_states_.resize(2, std::numeric_limits::queit_NaN()); // hw_velocity_states_.resize(2, std::numeric_limits::queit_NaN()); - return hardware_interface::CallbackReturn::SUCCESS; } @@ -186,9 +181,8 @@ std::vector CarlikeBotSystemHardware::export // get the index of the joint name in hw_interfaces_ auto it = std::find_if( hw_interfaces_.begin(), hw_interfaces_.end(), - [this, i](const std::tuple & element) { - return std::get<0>(element) == info_.joints[i].name; - }); + [this, i](const std::tuple & element) + { return std::get<0>(element) == info_.joints[i].name; }); if (joint_is_steering) { @@ -234,9 +228,8 @@ CarlikeBotSystemHardware::export_command_interfaces() // get the index of the joint name in hw_interfaces_ auto it = std::find_if( hw_interfaces_.begin(), hw_interfaces_.end(), - [this, i](const std::tuple & element) { - return std::get<0>(element) == info_.joints[i].name; - }); + [this, i](const std::tuple & element) + { return std::get<0>(element) == info_.joints[i].name; }); if (joint_is_steering) { @@ -346,8 +339,8 @@ hardware_interface::return_type ros2_control_demo_example_11 ::CarlikeBotSystemH std::get<2>(hw_interfaces_[i]) = std::get<2>(hw_interfaces_[i]); // RCLCPP_INFO( - // rclcpp::get_logger("CarlikeBotSystemHardware"), "Got command %.5f for '%s'", hw_commands_[i], - // info_.joints[i].name.c_str()); + // rclcpp::get_logger("CarlikeBotSystemHardware"), "Got command %.5f for '%s'", + // hw_commands_[i], info_.joints[i].name.c_str()); } return hardware_interface::return_type::OK; diff --git a/example_11/hardware/include/ros2_control_demo_example_11/carlikebot_system.hpp b/example_11/hardware/include/ros2_control_demo_example_11/carlikebot_system.hpp index 76ad73afc..4ee874307 100644 --- a/example_11/hardware/include/ros2_control_demo_example_11/carlikebot_system.hpp +++ b/example_11/hardware/include/ros2_control_demo_example_11/carlikebot_system.hpp @@ -82,7 +82,8 @@ class CarlikeBotSystemHardware : public hardware_interface::SystemInterface // std::vector hw_commands_; // std::vector hw_states_; - std::vector> hw_interfaces_; // name of joint, state, command + std::vector> + hw_interfaces_; // name of joint, state, command // std::vector> commands_counterpart_;