From 8671938530c48dae39dd77cdcdfd4862bef44a22 Mon Sep 17 00:00:00 2001 From: ipa-vsp Date: Sat, 17 Aug 2024 11:53:50 +0200 Subject: [PATCH] pre-commit fix --- .../node_interfaces/node_canopen_402_driver.hpp | 2 +- .../node_canopen_402_driver_impl.hpp | 2 +- canopen_ros2_control/src/cia402_system.cpp | 15 ++++++++++----- 3 files changed, 12 insertions(+), 7 deletions(-) diff --git a/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp b/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp index 05187edd..36f31741 100644 --- a/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp +++ b/canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp @@ -161,7 +161,7 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver * * Calls Motor402::enterModeAndWait with requested Operation Mode. * - * @param [in] request Requested Operation Mode as MotorBase::Profiled_Position or + * @param [in] request Requested Operation Mode as MotorBase::Profiled_Position or * MotorBase::Profiled_Velocity or MotorBase::Profiled_Torque or MotorBase::Cyclic_Position or * MotorBase::Cyclic_Velocity or MotorBase::Cyclic_Torque or MotorBase::Interpolated_Position * @param [out] response 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 23c26ee4..fcd2d35d 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 @@ -509,7 +509,7 @@ bool NodeCanopen402Driver::set_operation_mode(uint16_t mode) { if (this->activated_.load()) { - if(motor_->getMode() != mode) + if (motor_->getMode() != mode) { return motor_->enterModeAndWait(mode); } diff --git a/canopen_ros2_control/src/cia402_system.cpp b/canopen_ros2_control/src/cia402_system.cpp index fef2232b..8c0cc6f2 100644 --- a/canopen_ros2_control/src/cia402_system.cpp +++ b/canopen_ros2_control/src/cia402_system.cpp @@ -330,27 +330,32 @@ void Cia402System::switchModes(uint id, const std::shared_ptrset_operation_mode(MotorBase::Profiled_Position)); + motor_data_[id].position_mode.set_response( + driver->set_operation_mode(MotorBase::Profiled_Position)); } if (motor_data_[id].cyclic_position_mode.is_commanded()) { - motor_data_[id].cyclic_position_mode.set_response(driver->set_operation_mode(MotorBase::Cyclic_Synchronous_Position)); + motor_data_[id].cyclic_position_mode.set_response( + driver->set_operation_mode(MotorBase::Cyclic_Synchronous_Position)); } if (motor_data_[id].velocity_mode.is_commanded()) { - motor_data_[id].velocity_mode.set_response(driver->set_operation_mode(MotorBase::Profiled_Velocity)); + motor_data_[id].velocity_mode.set_response( + driver->set_operation_mode(MotorBase::Profiled_Velocity)); } if (motor_data_[id].cyclic_velocity_mode.is_commanded()) { - motor_data_[id].cyclic_velocity_mode.set_response(driver->set_operation_mode(MotorBase::Cyclic_Synchronous_Velocity)); + motor_data_[id].cyclic_velocity_mode.set_response( + driver->set_operation_mode(MotorBase::Cyclic_Synchronous_Velocity)); } if (motor_data_[id].torque_mode.is_commanded()) { - motor_data_[id].torque_mode.set_response(driver->set_operation_mode(MotorBase::Profiled_Torque)); + motor_data_[id].torque_mode.set_response( + driver->set_operation_mode(MotorBase::Profiled_Torque)); } if (motor_data_[id].interpolated_position_mode.is_commanded())