Skip to content

Commit e269518

Browse files
committed
Fix Format
1 parent b7efaa4 commit e269518

File tree

3 files changed

+17
-18
lines changed

3 files changed

+17
-18
lines changed

ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -119,5 +119,5 @@ class FreedriveModeController : public controller_interface::ControllerInterface
119119
*/
120120
bool waitForAsyncCommand(std::function<double(void)> get_value);
121121
};
122-
} // namespace ur_controllers
123-
#endif // UR_CONTROLLERS__PASSTHROUGH_TRAJECTORY_CONTROLLER_HPP_
122+
} // namespace ur_controllers
123+
#endif // UR_CONTROLLERS__PASSTHROUGH_TRAJECTORY_CONTROLLER_HPP_

ur_controllers/src/freedrive_mode_controller.cpp

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,8 @@ controller_interface::InterfaceConfiguration FreedriveModeController::command_in
7171
return config;
7272
}
7373

74-
controller_interface::InterfaceConfiguration ur_controllers::FreedriveModeController::state_interface_configuration() const
74+
controller_interface::InterfaceConfiguration
75+
ur_controllers::FreedriveModeController::state_interface_configuration() const
7576
{
7677
controller_interface::InterfaceConfiguration config;
7778
config.type = controller_interface::interface_configuration_type::NONE;
@@ -82,7 +83,6 @@ controller_interface::InterfaceConfiguration ur_controllers::FreedriveModeContro
8283
controller_interface::CallbackReturn
8384
ur_controllers::FreedriveModeController::on_configure(const rclcpp_lifecycle::State& previous_state)
8485
{
85-
8686
// Subscriber definition
8787
enable_freedrive_mode_sub_ = get_node()->create_subscription<std_msgs::msg::Bool>(
8888
"~/freedrive_mode_active", 10,
@@ -164,7 +164,7 @@ ur_controllers::FreedriveModeController::on_deactivate(const rclcpp_lifecycle::S
164164

165165
// Set enable value to false, so in the update
166166
// we can deactivate the freedrive mode
167-
//Old comment?
167+
// Old comment?
168168
freedrive_active_ = false;
169169

170170
return CallbackReturn::SUCCESS;
@@ -177,15 +177,14 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
177177

178178
if(change_requested_) {
179179
if (freedrive_active_) {
180-
// Check if the freedrive mode has been aborted from the hardware interface. E.g. the robot was stopped on the teach
181-
// pendant.
180+
// Check if the freedrive mode has been aborted from the hardware interface. E.g. the robot was stopped on the
181+
// teach pendant.
182182
if (!std::isnan(abort_command_interface_->get().get_value()) &&
183183
abort_command_interface_->get().get_value() == 1.0) {
184184
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode aborted by hardware, aborting action.");
185185
freedrive_active_ = false;
186186
return controller_interface::return_type::OK;
187187
} else {
188-
189188
RCLCPP_INFO(get_node()->get_logger(), "Received command to start Freedrive Mode.");
190189

191190
// Set command interface to enable
@@ -220,7 +219,6 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
220219

221220
void FreedriveModeController::readFreedriveModeCmd(const std_msgs::msg::Bool::SharedPtr msg)
222221
{
223-
224222
// Process the freedrive_mode command.
225223
if(msg->data)
226224
{
@@ -259,7 +257,6 @@ void FreedriveModeController::start_timer()
259257

260258
void FreedriveModeController::timeout_callback()
261259
{
262-
263260
if(timer_started_){
264261
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode will be deactivated since client is not reachable.");
265262

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -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

894896
void URPositionHardwareInterface::extractToolPose()
@@ -907,7 +909,7 @@ void URPositionHardwareInterface::extractToolPose()
907909
}
908910

909911
hardware_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

Comments
 (0)