Skip to content

Commit

Permalink
pre-commit fix
Browse files Browse the repository at this point in the history
  • Loading branch information
ipa-vsp committed Aug 17, 2024
1 parent 5041853 commit 8671938
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ class NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>
*
* 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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -509,7 +509,7 @@ bool NodeCanopen402Driver<NODETYPE>::set_operation_mode(uint16_t mode)
{
if (this->activated_.load())
{
if(motor_->getMode() != mode)
if (motor_->getMode() != mode)
{
return motor_->enterModeAndWait(mode);
}
Expand Down
15 changes: 10 additions & 5 deletions canopen_ros2_control/src/cia402_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,27 +330,32 @@ void Cia402System::switchModes(uint id, const std::shared_ptr<ros2_canopen::Cia4
{
if (motor_data_[id].position_mode.is_commanded())
{
motor_data_[id].position_mode.set_response(driver->set_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())
Expand Down

0 comments on commit 8671938

Please sign in to comment.