Skip to content

Commit

Permalink
fox code format using pre-commit
Browse files Browse the repository at this point in the history
  • Loading branch information
synsi23b committed Aug 27, 2024
1 parent eea1c28 commit c3cb00f
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 6 deletions.
5 changes: 4 additions & 1 deletion canopen_402_driver/include/canopen_402_driver/motor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,10 @@ class Motor402 : public MotorBase
registerMode<CyclicSynchronousTorqueMode>(MotorBase::Cyclic_Synchronous_Torque, driver);
}

double get_effort() const { return (double)this->driver->universal_get_value<int16_t>(0x6077, 0); }
double get_effort() const
{
return (double)this->driver->universal_get_value<int16_t>(0x6077, 0);
}
double get_speed() const { return (double)this->driver->universal_get_value<int32_t>(0x606C, 0); }
double get_position() const
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -319,8 +319,10 @@ void NodeCanopen402Driver<rclcpp::Node>::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 <class NODETYPE>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
3 changes: 1 addition & 2 deletions canopen_ros2_control/src/cia402_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,8 +138,7 @@ std::vector<hardware_interface::StateInterface> 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;
Expand Down

0 comments on commit c3cb00f

Please sign in to comment.