@@ -834,15 +834,17 @@ void URPositionHardwareInterface::checkAsyncIO()
834834
835835 if (!std::isnan (freedrive_mode_enable_) && ur_driver_ != nullptr ) {
836836 RCLCPP_INFO (get_logger (), " Starting freedrive mode." );
837- freedrive_mode_async_success_ = ur_driver_->writeFreedriveControlMessage (urcl::control::FreedriveControlMessage::FREEDRIVE_START);
837+ freedrive_mode_async_success_ =
838+ ur_driver_->writeFreedriveControlMessage (urcl::control::FreedriveControlMessage::FREEDRIVE_START);
838839 freedrive_mode_enable_ = NO_NEW_CMD_;
839840 freedrive_action_requested_ = true ;
840841 }
841842
842843 if (!std::isnan (freedrive_mode_abort_) && freedrive_mode_abort_ == 1.0 && freedrive_action_requested_ &&
843844 ur_driver_ != nullptr ) {
844845 RCLCPP_INFO (get_logger (), " Stopping freedrive mode." );
845- freedrive_mode_async_success_ = ur_driver_->writeFreedriveControlMessage (urcl::control::FreedriveControlMessage::FREEDRIVE_STOP);
846+ freedrive_mode_async_success_ =
847+ ur_driver_->writeFreedriveControlMessage (urcl::control::FreedriveControlMessage::FREEDRIVE_STOP);
846848 freedrive_action_requested_ = false ;
847849 freedrive_mode_abort_ = NO_NEW_CMD_;
848850}
@@ -882,13 +884,13 @@ void URPositionHardwareInterface::transformForceTorque()
882884 tcp_force_.setValue (urcl_ft_sensor_measurements_[0 ], urcl_ft_sensor_measurements_[1 ],
883885 urcl_ft_sensor_measurements_[2 ]);
884886 tcp_torque_.setValue (urcl_ft_sensor_measurements_[3 ], urcl_ft_sensor_measurements_[4 ],
885- urcl_ft_sensor_measurements_[5 ]);
887+ urcl_ft_sensor_measurements_[5 ]);
886888
887889 tcp_force_ = tf2::quatRotate (tcp_rotation_quat_.inverse (), tcp_force_);
888890 tcp_torque_ = tf2::quatRotate (tcp_rotation_quat_.inverse (), tcp_torque_);
889891
890892 urcl_ft_sensor_measurements_ = { tcp_force_.x (), tcp_force_.y (), tcp_force_.z (),
891- tcp_torque_.x (), tcp_torque_.y (), tcp_torque_.z () };
893+ tcp_torque_.x (), tcp_torque_.y (), tcp_torque_.z () };
892894}
893895
894896void URPositionHardwareInterface::extractToolPose ()
@@ -907,7 +909,7 @@ void URPositionHardwareInterface::extractToolPose()
907909}
908910
909911hardware_interface::return_type URPositionHardwareInterface::prepare_command_mode_switch (
910- const std::vector<std::string>& start_interfaces, const std::vector<std::string>& stop_interfaces)
912+ const std::vector<std::string>& start_interfaces, const std::vector<std::string>& stop_interfaces)
911913{
912914 hardware_interface::return_type ret_val = hardware_interface::return_type::OK;
913915
@@ -1011,11 +1013,11 @@ hardware_interface::return_type URPositionHardwareInterface::prepare_command_mod
10111013 }))) {
10121014 ret_val = hardware_interface::return_type::ERROR;
10131015 }
1014- if (std::any_of (start_modes_.begin (), start_modes_.end (),
1015- [this ](auto & item) { return (item == FREEDRIVE_MODE); }) &&
1016+ if (std::any_of (start_modes_.begin (), start_modes_.end (), [this ](auto & item) { return (item == FREEDRIVE_MODE); }) &&
10161017 (std::any_of (start_modes_.begin (), start_modes_.end (),
10171018 [this ](auto & item) {
1018- return (item == hardware_interface::HW_IF_VELOCITY || item == hardware_interface::HW_IF_POSITION || item == PASSTHROUGH_GPIO);
1019+ return (item == hardware_interface::HW_IF_VELOCITY || item == hardware_interface::HW_IF_POSITION ||
1020+ item == PASSTHROUGH_GPIO);
10191021 }) ||
10201022 std::any_of (control_modes.begin (), control_modes.end (), [this ](auto & item) {
10211023 return (item == hardware_interface::HW_IF_VELOCITY || item == hardware_interface::HW_IF_POSITION ||
0 commit comments