From c3cb00f46198c7a8eba668121bd29b5c67c7353e Mon Sep 17 00:00:00 2001 From: synsi Date: Tue, 27 Aug 2024 10:46:12 +0900 Subject: [PATCH] fox code format using pre-commit --- canopen_402_driver/include/canopen_402_driver/motor.hpp | 5 ++++- .../node_interfaces/node_canopen_402_driver_impl.hpp | 6 ++++-- .../include/canopen_ros2_control/cia402_data.hpp | 2 +- canopen_ros2_control/src/cia402_system.cpp | 3 +-- 4 files changed, 10 insertions(+), 6 deletions(-) diff --git a/canopen_402_driver/include/canopen_402_driver/motor.hpp b/canopen_402_driver/include/canopen_402_driver/motor.hpp index 05f67eb1..1a741a0b 100644 --- a/canopen_402_driver/include/canopen_402_driver/motor.hpp +++ b/canopen_402_driver/include/canopen_402_driver/motor.hpp @@ -174,7 +174,10 @@ class Motor402 : public MotorBase registerMode(MotorBase::Cyclic_Synchronous_Torque, driver); } - double get_effort() const { return (double)this->driver->universal_get_value(0x6077, 0); } + double get_effort() const + { + return (double)this->driver->universal_get_value(0x6077, 0); + } double get_speed() const { return (double)this->driver->universal_get_value(0x606C, 0); } double get_position() const { diff --git a/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver_impl.hpp b/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver_impl.hpp index a6d570d4..c36a8f2b 100644 --- a/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver_impl.hpp +++ b/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver_impl.hpp @@ -319,8 +319,10 @@ void NodeCanopen402Driver::configure(bool called_from_base) (int)ros2_canopen::State402::InternalState::Operation_Enable); RCLCPP_INFO( this->node_->get_logger(), - "scale_pos_to_dev_ %f\nscale_pos_from_dev_ %f\nscale_vel_to_dev_ %f\nscale_vel_from_dev_ %f\nscale_eff_from_dev_ %f\n", - scale_pos_to_dev_, scale_pos_from_dev_, scale_vel_to_dev_, scale_vel_from_dev_, scale_eff_from_dev_); + "scale_pos_to_dev_ %f\nscale_pos_from_dev_ %f\nscale_vel_to_dev_ %f\nscale_vel_from_dev_ " + "%f\nscale_eff_from_dev_ %f\n", + scale_pos_to_dev_, scale_pos_from_dev_, scale_vel_to_dev_, scale_vel_from_dev_, + scale_eff_from_dev_); } template diff --git a/canopen_ros2_control/include/canopen_ros2_control/cia402_data.hpp b/canopen_ros2_control/include/canopen_ros2_control/cia402_data.hpp index 39129688..fd962876 100644 --- a/canopen_ros2_control/include/canopen_ros2_control/cia402_data.hpp +++ b/canopen_ros2_control/include/canopen_ros2_control/cia402_data.hpp @@ -108,7 +108,7 @@ struct Cia402Data // actual speed state_interfaces.emplace_back(hardware_interface::StateInterface( joint_name, hardware_interface::HW_IF_VELOCITY, &actual_velocity)); - + // actual effort state_interfaces.emplace_back(hardware_interface::StateInterface( joint_name, hardware_interface::HW_IF_EFFORT, &actual_effort)); diff --git a/canopen_ros2_control/src/cia402_system.cpp b/canopen_ros2_control/src/cia402_system.cpp index a9d72485..7e69f981 100644 --- a/canopen_ros2_control/src/cia402_system.cpp +++ b/canopen_ros2_control/src/cia402_system.cpp @@ -138,8 +138,7 @@ std::vector Cia402System::export_state_inter &motor_data_[node_id].actual_speed)); // actual effort state_interfaces.emplace_back(hardware_interface::StateInterface( - info_.joints[i].name, hardware_interface::HW_IF_EFFORT, - &motor_data_[node_id].actual_effort)); + info_.joints[i].name, hardware_interface::HW_IF_EFFORT, &motor_data_[node_id].actual_effort)); } return state_interfaces;