Skip to content

Commit 920e60f

Browse files
committed
Updated variable name to meaningful one
1 parent 2976181 commit 920e60f

File tree

2 files changed

+7
-7
lines changed

2 files changed

+7
-7
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
227227
double get_robot_software_version_build_;
228228

229229
// Freedrive mode controller interface values
230-
bool freedrive_action_requested_;
230+
bool freedrive_activated_;
231231
bool freedrive_mode_controller_running_;
232232
double freedrive_mode_async_success_;
233233
double freedrive_mode_enable_;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -721,7 +721,7 @@ hardware_interface::return_type URPositionHardwareInterface::write(const rclcpp:
721721
} else if (velocity_controller_running_) {
722722
ur_driver_->writeJointCommand(urcl_velocity_commands_, urcl::comm::ControlMode::MODE_SPEEDJ, receive_timeout_);
723723

724-
} else if (freedrive_mode_controller_running_ && freedrive_action_requested_) {
724+
} else if (freedrive_mode_controller_running_ && freedrive_activated_) {
725725
ur_driver_->writeFreedriveControlMessage(urcl::control::FreedriveControlMessage::FREEDRIVE_NOOP);
726726

727727
} else if (passthrough_trajectory_controller_running_) {
@@ -837,15 +837,15 @@ void URPositionHardwareInterface::checkAsyncIO()
837837
freedrive_mode_async_success_ =
838838
ur_driver_->writeFreedriveControlMessage(urcl::control::FreedriveControlMessage::FREEDRIVE_START);
839839
freedrive_mode_enable_ = NO_NEW_CMD_;
840-
freedrive_action_requested_ = true;
840+
freedrive_activated_ = true;
841841
}
842842

843-
if (!std::isnan(freedrive_mode_abort_) && freedrive_mode_abort_ == 1.0 && freedrive_action_requested_ &&
843+
if (!std::isnan(freedrive_mode_abort_) && freedrive_mode_abort_ == 1.0 && freedrive_activated_ &&
844844
ur_driver_ != nullptr) {
845845
RCLCPP_INFO(get_logger(), "Stopping freedrive mode.");
846846
freedrive_mode_async_success_ =
847847
ur_driver_->writeFreedriveControlMessage(urcl::control::FreedriveControlMessage::FREEDRIVE_STOP);
848-
freedrive_action_requested_ = false;
848+
freedrive_activated_ = false;
849849
freedrive_mode_abort_ = NO_NEW_CMD_;
850850
}
851851
}
@@ -1069,7 +1069,7 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
10691069
} else if (stop_modes_.size() != 0 && std::find(stop_modes_.begin(), stop_modes_.end(),
10701070
StoppingInterface::STOP_FREEDRIVE) != stop_modes_.end()) {
10711071
freedrive_mode_controller_running_ = false;
1072-
freedrive_action_requested_ = false;
1072+
freedrive_activated_ = false;
10731073
freedrive_mode_abort_ = 1.0;
10741074
} else if (stop_modes_.size() != 0 && std::find(stop_modes_.begin(), stop_modes_.end(),
10751075
StoppingInterface::STOP_PASSTHROUGH) != stop_modes_.end()) {
@@ -1098,7 +1098,7 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
10981098
velocity_controller_running_ = false;
10991099
position_controller_running_ = false;
11001100
freedrive_mode_controller_running_ = true;
1101-
freedrive_action_requested_ = false;
1101+
freedrive_activated_ = false;
11021102
} else if (start_modes_.size() != 0 &&
11031103
std::find(start_modes_.begin(), start_modes_.end(), PASSTHROUGH_GPIO) != start_modes_.end()) {
11041104
velocity_controller_running_ = false;

0 commit comments

Comments
 (0)