Skip to content

Commit 67f2256

Browse files
committed
Fix formatting
1 parent a8cb789 commit 67f2256

File tree

2 files changed

+47
-53
lines changed

2 files changed

+47
-53
lines changed

ur_controllers/include/ur_controllers/freedrive_mode_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@ enum CommandInterfaces
6464
FREEDRIVE_MODE_ABORT = 2,
6565
};
6666

67-
using namespace std::chrono_literals; // NOLINT
67+
using namespace std::chrono_literals; // NOLINT
6868

6969
class FreedriveModeController : public controller_interface::ControllerInterface
7070
{

ur_controllers/src/freedrive_mode_controller.cpp

Lines changed: 46 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
122122

123123
{
124124
const std::string interface_name = freedrive_params_.tf_prefix + "freedrive_mode/"
125-
"async_success";
125+
"async_success";
126126
auto it = std::find_if(command_interfaces_.begin(), command_interfaces_.end(),
127127
[&](auto& interface) { return (interface.get_name() == interface_name); });
128128
if (it != command_interfaces_.end()) {
@@ -135,7 +135,7 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
135135

136136
{
137137
const std::string interface_name = freedrive_params_.tf_prefix + "freedrive_mode/"
138-
"enable";
138+
"enable";
139139
auto it = std::find_if(command_interfaces_.begin(), command_interfaces_.end(),
140140
[&](auto& interface) { return (interface.get_name() == interface_name); });
141141
if (it != command_interfaces_.end()) {
@@ -148,7 +148,7 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
148148

149149
{
150150
const std::string interface_name = freedrive_params_.tf_prefix + "freedrive_mode/"
151-
"abort";
151+
"abort";
152152
auto it = std::find_if(command_interfaces_.begin(), command_interfaces_.end(),
153153
[&](auto& interface) { return (interface.get_name() == interface_name); });
154154
if (it != command_interfaces_.end()) {
@@ -178,11 +178,11 @@ ur_controllers::FreedriveModeController::on_deactivate(const rclcpp_lifecycle::S
178178
}
179179

180180
controller_interface::return_type ur_controllers::FreedriveModeController::update(const rclcpp::Time& /*time*/,
181-
const rclcpp::Duration& /*period*/)
181+
const rclcpp::Duration& /*period*/)
182182
{
183183
async_state_ = async_success_command_interface_->get().get_value();
184184

185-
if(change_requested_) {
185+
if (change_requested_) {
186186
if (freedrive_active_) {
187187
// Check if the freedrive mode has been aborted from the hardware interface. E.g. the robot was stopped on the
188188
// teach pendant.
@@ -213,51 +213,45 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
213213
change_requested_ = false;
214214
}
215215

216-
if((async_state_ == 1.0) && (first_log_)){
216+
if ((async_state_ == 1.0) && (first_log_)) {
217217
first_log_ = false;
218-
logging_requested_= true;
218+
logging_requested_ = true;
219219

220220
// Notify logging thread
221221
logging_condition_.notify_one();
222-
223222
}
224223
return controller_interface::return_type::OK;
225224
}
226225

227226
void FreedriveModeController::readFreedriveModeCmd(const std_msgs::msg::Bool::SharedPtr msg)
228227
{
229228
// Process the freedrive_mode command.
230-
if (get_node()->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
231-
{
232-
if(msg->data)
233-
{
234-
if((!freedrive_active_) && (!change_requested_)){
229+
if (get_node()->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
230+
if (msg->data) {
231+
if ((!freedrive_active_) && (!change_requested_)) {
235232
freedrive_active_ = true;
236233
change_requested_ = true;
237234
start_timer();
238235
}
239-
} else{
240-
if((freedrive_active_) && (!change_requested_)){
236+
} else {
237+
if ((freedrive_active_) && (!change_requested_)) {
241238
freedrive_active_ = false;
242239
change_requested_ = true;
243240
}
244241
}
245242
}
246243

247-
if (freedrive_sub_timer_)
248-
{
244+
if (freedrive_sub_timer_) {
249245
freedrive_sub_timer_->reset();
250246
}
251247
}
252248

253249
void FreedriveModeController::start_timer()
254250
{
255-
if (!timer_started_)
256-
{
251+
if (!timer_started_) {
257252
// Start the timer only after the first message is received
258-
freedrive_sub_timer_ = get_node()->create_wall_timer(
259-
timeout_interval_,
260-
std::bind(&FreedriveModeController::timeout_callback, this));
253+
freedrive_sub_timer_ =
254+
get_node()->create_wall_timer(timeout_interval_, std::bind(&FreedriveModeController::timeout_callback, this));
261255
timer_started_ = true;
262256

263257
RCLCPP_INFO(get_node()->get_logger(), "Timer started after receiving first command.");
@@ -266,7 +260,7 @@ void FreedriveModeController::start_timer()
266260

267261
void FreedriveModeController::timeout_callback()
268262
{
269-
if(timer_started_ && freedrive_active_){
263+
if (timer_started_ && freedrive_active_) {
270264
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode will be deactivated since client is not reachable.");
271265

272266
freedrive_active_ = false;
@@ -276,45 +270,45 @@ void FreedriveModeController::timeout_callback()
276270
timer_started_ = false;
277271
}
278272

279-
void FreedriveModeController::start_logging_thread() {
280-
if (!logging_thread_running_) {
281-
logging_thread_running_ = true;
282-
logging_thread_ = std::thread(&FreedriveModeController::log_task, this);
283-
}
273+
void FreedriveModeController::start_logging_thread()
274+
{
275+
if (!logging_thread_running_) {
276+
logging_thread_running_ = true;
277+
logging_thread_ = std::thread(&FreedriveModeController::log_task, this);
284278
}
279+
}
285280

286-
void FreedriveModeController::stop_logging_thread() {
287-
logging_thread_running_ = false;
288-
if (logging_thread_.joinable()) {
289-
logging_thread_.join();
290-
}
281+
void FreedriveModeController::stop_logging_thread()
282+
{
283+
logging_thread_running_ = false;
284+
if (logging_thread_.joinable()) {
285+
logging_thread_.join();
291286
}
287+
}
292288

293-
void FreedriveModeController::log_task() {
294-
while (logging_thread_running_) {
295-
296-
std::unique_lock<std::mutex> lock(log_mutex_);
297-
298-
auto condition = [this] {
299-
return !logging_thread_running_ || logging_requested_;
300-
};
289+
void FreedriveModeController::log_task()
290+
{
291+
while (logging_thread_running_) {
292+
std::unique_lock<std::mutex> lock(log_mutex_);
301293

302-
// Wait for the condition
303-
logging_condition_.wait(lock, condition);
294+
auto condition = [this] { return !logging_thread_running_ || logging_requested_; };
304295

296+
// Wait for the condition
297+
logging_condition_.wait(lock, condition);
305298

306-
if (!logging_thread_running_) break;
299+
if (!logging_thread_running_)
300+
break;
307301

308-
if(freedrive_active_){
309-
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode has been enabled successfully.");
310-
} else {
311-
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode has been disabled successfully.");
312-
}
313-
314-
// Reset to log only once
315-
logging_requested_ = false;
302+
if (freedrive_active_) {
303+
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode has been enabled successfully.");
304+
} else {
305+
RCLCPP_INFO(get_node()->get_logger(), "Freedrive mode has been disabled successfully.");
316306
}
307+
308+
// Reset to log only once
309+
logging_requested_ = false;
317310
}
311+
}
318312

319313
bool FreedriveModeController::waitForAsyncCommand(std::function<double(void)> get_value)
320314
{

0 commit comments

Comments
 (0)