Skip to content

Commit 542105b

Browse files
committed
Handle nodiscard return value of command_interface.set_value
Fail the controller function if writing to a command interface fails. For the GPIO controller we ignore the return value, as we are checking the result anyway.
1 parent 9289769 commit 542105b

File tree

5 files changed

+145
-85
lines changed

5 files changed

+145
-85
lines changed

ur_controllers/src/force_mode_controller.cpp

Lines changed: 62 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,9 @@ controller_interface::CallbackReturn
156156
ur_controllers::ForceModeController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
157157
{
158158
// Stop force mode if this controller is deactivated.
159-
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
159+
if (!command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0)) {
160+
return LifecycleNodeInterface::CallbackReturn::ERROR;
161+
}
160162
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
161163
}
162164

@@ -175,54 +177,80 @@ controller_interface::return_type ur_controllers::ForceModeController::update(co
175177

176178
// Publish state of force_mode?
177179
if (change_requested_) {
180+
bool write_successful = true;
178181
if (force_mode_active_) {
179182
const auto force_mode_parameters = force_mode_params_buffer_.readFromRT();
180-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(force_mode_parameters->task_frame[0]);
181-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(force_mode_parameters->task_frame[1]);
182-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value(force_mode_parameters->task_frame[2]);
183-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value(force_mode_parameters->task_frame[3]);
184-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value(force_mode_parameters->task_frame[4]);
185-
command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value(force_mode_parameters->task_frame[5]);
186-
187-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value(
183+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_X].set_value(
184+
force_mode_parameters->task_frame[0]);
185+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Y].set_value(
186+
force_mode_parameters->task_frame[1]);
187+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_Z].set_value(
188+
force_mode_parameters->task_frame[2]);
189+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RX].set_value(
190+
force_mode_parameters->task_frame[3]);
191+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RY].set_value(
192+
force_mode_parameters->task_frame[4]);
193+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_TASK_FRAME_RZ].set_value(
194+
force_mode_parameters->task_frame[5]);
195+
196+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_X].set_value(
188197
force_mode_parameters->selection_vec[0]);
189-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value(
198+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Y].set_value(
190199
force_mode_parameters->selection_vec[1]);
191-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value(
200+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_Z].set_value(
192201
force_mode_parameters->selection_vec[2]);
193-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value(
202+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RX].set_value(
194203
force_mode_parameters->selection_vec[3]);
195-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value(
204+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RY].set_value(
196205
force_mode_parameters->selection_vec[4]);
197-
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
206+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
198207
force_mode_parameters->selection_vec[5]);
199208

200-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
201-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
202-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
203-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(force_mode_parameters->wrench.torque.x);
204-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(force_mode_parameters->wrench.torque.y);
205-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(force_mode_parameters->wrench.torque.z);
206-
207-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
208-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);
209-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value(force_mode_parameters->limits[2]);
210-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value(force_mode_parameters->limits[3]);
211-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value(force_mode_parameters->limits[4]);
212-
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value(force_mode_parameters->limits[5]);
213-
214-
command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(force_mode_parameters->type);
215-
command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value(force_mode_parameters->damping_factor);
216-
command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value(force_mode_parameters->gain_scaling);
209+
write_successful &=
210+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
211+
write_successful &=
212+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
213+
write_successful &=
214+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
215+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(
216+
force_mode_parameters->wrench.torque.x);
217+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(
218+
force_mode_parameters->wrench.torque.y);
219+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(
220+
force_mode_parameters->wrench.torque.z);
221+
222+
write_successful &=
223+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
224+
write_successful &=
225+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);
226+
write_successful &=
227+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Z].set_value(force_mode_parameters->limits[2]);
228+
write_successful &=
229+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RX].set_value(force_mode_parameters->limits[3]);
230+
write_successful &=
231+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RY].set_value(force_mode_parameters->limits[4]);
232+
write_successful &=
233+
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_RZ].set_value(force_mode_parameters->limits[5]);
234+
235+
write_successful &=
236+
command_interfaces_[CommandInterfaces::FORCE_MODE_TYPE].set_value(force_mode_parameters->type);
237+
write_successful &=
238+
command_interfaces_[CommandInterfaces::FORCE_MODE_DAMPING].set_value(force_mode_parameters->damping_factor);
239+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_GAIN_SCALING].set_value(
240+
force_mode_parameters->gain_scaling);
217241

218242
// Signal that we are waiting for confirmation that force mode is activated
219-
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
243+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
220244
async_state_ = ASYNC_WAITING;
221245
} else {
222-
command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
223-
command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
246+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_DISABLE_CMD].set_value(1.0);
247+
write_successful &= command_interfaces_[CommandInterfaces::FORCE_MODE_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
224248
async_state_ = ASYNC_WAITING;
225249
}
250+
if (!write_successful) {
251+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to a command interfaces.");
252+
return controller_interface::return_type::ERROR;
253+
}
226254
change_requested_ = false;
227255
}
228256

ur_controllers/src/freedrive_mode_controller.cpp

Lines changed: 18 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -153,7 +153,10 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
153153
[&](auto& interface) { return (interface.get_name() == interface_name); });
154154
if (it != command_interfaces_.end()) {
155155
abort_command_interface_ = *it;
156-
abort_command_interface_->get().set_value(0.0);
156+
if (!abort_command_interface_->get().set_value(0.0)) {
157+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to abort command interface.");
158+
return controller_interface::CallbackReturn::ERROR;
159+
}
157160
} else {
158161
RCLCPP_ERROR(get_node()->get_logger(), "Did not find '%s' in command interfaces.", interface_name.c_str());
159162
return controller_interface::CallbackReturn::ERROR;
@@ -166,7 +169,10 @@ ur_controllers::FreedriveModeController::on_activate(const rclcpp_lifecycle::Sta
166169
controller_interface::CallbackReturn
167170
ur_controllers::FreedriveModeController::on_cleanup(const rclcpp_lifecycle::State& /*previous_state*/)
168171
{
169-
abort_command_interface_->get().set_value(1.0);
172+
if (!abort_command_interface_->get().set_value(1.0)) {
173+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to abort command interface.");
174+
return controller_interface::CallbackReturn::ERROR;
175+
}
170176

171177
stop_logging_thread();
172178

@@ -190,6 +196,7 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
190196
async_state_ = async_success_command_interface_->get().get_value();
191197

192198
if (change_requested_) {
199+
bool write_success = true;
193200
if (freedrive_active_) {
194201
// Check if the freedrive mode has been aborted from the hardware interface. E.g. the robot was stopped on the
195202
// teach pendant.
@@ -202,22 +209,27 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
202209
RCLCPP_INFO(get_node()->get_logger(), "Received command to start Freedrive Mode.");
203210

204211
// Set command interface to enable
205-
enable_command_interface_->get().set_value(1.0);
212+
write_success &= enable_command_interface_->get().set_value(1.0);
206213

207-
async_success_command_interface_->get().set_value(ASYNC_WAITING);
214+
write_success &= async_success_command_interface_->get().set_value(ASYNC_WAITING);
208215
async_state_ = ASYNC_WAITING;
209216
}
210217

211218
} else {
212219
RCLCPP_INFO(get_node()->get_logger(), "Received command to stop Freedrive Mode.");
213220

214-
abort_command_interface_->get().set_value(1.0);
221+
write_success &= abort_command_interface_->get().set_value(1.0);
215222

216-
async_success_command_interface_->get().set_value(ASYNC_WAITING);
223+
write_success &= async_success_command_interface_->get().set_value(ASYNC_WAITING);
217224
async_state_ = ASYNC_WAITING;
218225
}
219226
first_log_ = true;
220227
change_requested_ = false;
228+
229+
if (!write_success) {
230+
RCLCPP_ERROR(get_node()->get_logger(), "Could not write to a command interfaces.");
231+
return controller_interface::return_type::ERROR;
232+
}
221233
}
222234

223235
if ((async_state_ == 1.0) && (first_log_)) {

ur_controllers/src/gpio_controller.cpp

Lines changed: 25 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -345,8 +345,8 @@ bool GPIOController::setIO(ur_msgs::srv::SetIO::Request::SharedPtr req, ur_msgs:
345345
{
346346
if (req->fun == req->FUN_SET_DIGITAL_OUT && req->pin >= 0 && req->pin <= 17) {
347347
// io async success
348-
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
349-
command_interfaces_[req->pin].set_value(static_cast<double>(req->state));
348+
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
349+
std::ignore = command_interfaces_[req->pin].set_value(static_cast<double>(req->state));
350350

351351
RCLCPP_INFO(get_node()->get_logger(), "Setting digital output '%d' to state: '%1.0f'.", req->pin, req->state);
352352

@@ -359,8 +359,9 @@ bool GPIOController::setIO(ur_msgs::srv::SetIO::Request::SharedPtr req, ur_msgs:
359359
return resp->success;
360360
} else if (req->fun == req->FUN_SET_ANALOG_OUT && req->pin >= 0 && req->pin <= 2) {
361361
// io async success
362-
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
363-
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->pin].set_value(static_cast<double>(req->state));
362+
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
363+
std::ignore = command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->pin].set_value(
364+
static_cast<double>(req->state));
364365

365366
RCLCPP_INFO(get_node()->get_logger(), "Setting analog output '%d' to state: '%f'.", req->pin, req->state);
366367

@@ -372,8 +373,8 @@ bool GPIOController::setIO(ur_msgs::srv::SetIO::Request::SharedPtr req, ur_msgs:
372373
resp->success = static_cast<bool>(command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].get_value());
373374
return resp->success;
374375
} else if (req->fun == req->FUN_SET_TOOL_VOLTAGE) {
375-
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
376-
command_interfaces_[CommandInterfaces::TOOL_VOLTAGE_CMD].set_value(static_cast<double>(req->state));
376+
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
377+
std::ignore = command_interfaces_[CommandInterfaces::TOOL_VOLTAGE_CMD].set_value(static_cast<double>(req->state));
377378

378379
RCLCPP_INFO(get_node()->get_logger(), "Setting tool voltage to: '%1.0f'.", req->state);
379380

@@ -407,16 +408,17 @@ bool GPIOController::setAnalogOutput(ur_msgs::srv::SetAnalogOutput::Request::Sha
407408
return false;
408409
}
409410

410-
if (req->data.pin < 0 || req->data.pin > 1) {
411+
if (!(req->data.pin == 0 || req->data.pin == 1)) {
411412
RCLCPP_ERROR(get_node()->get_logger(), "Invalid pin selected. Only pins 0 and 1 are allowed.");
412413
resp->success = false;
413414
return false;
414415
}
415416

416-
command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
417-
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->data.pin].set_value(
417+
std::ignore = command_interfaces_[CommandInterfaces::IO_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
418+
std::ignore = command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_CMD + req->data.pin].set_value(
418419
static_cast<float>(req->data.state));
419-
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_DOMAIN].set_value(static_cast<double>(req->data.domain));
420+
std::ignore =
421+
command_interfaces_[CommandInterfaces::ANALOG_OUTPUTS_DOMAIN].set_value(static_cast<double>(req->data.domain));
420422

421423
RCLCPP_INFO(get_node()->get_logger(), "Setting analog output '%d' to state: '%f' in domain %s.", req->data.pin,
422424
req->data.state, domain_string.c_str());
@@ -436,9 +438,9 @@ bool GPIOController::setSpeedSlider(ur_msgs::srv::SetSpeedSliderFraction::Reques
436438
if (req->speed_slider_fraction >= 0.01 && req->speed_slider_fraction <= 1.0) {
437439
RCLCPP_INFO(get_node()->get_logger(), "Setting speed slider to %.2f%%.", req->speed_slider_fraction * 100.0);
438440
// reset success flag
439-
command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
441+
std::ignore = command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
440442
// set commanding value for speed slider
441-
command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_CMD].set_value(
443+
std::ignore = command_interfaces_[CommandInterfaces::TARGET_SPEED_FRACTION_CMD].set_value(
442444
static_cast<double>(req->speed_slider_fraction));
443445

444446
if (!waitForAsyncCommand([&]() {
@@ -462,9 +464,9 @@ bool GPIOController::resendRobotProgram(std_srvs::srv::Trigger::Request::SharedP
462464
std_srvs::srv::Trigger::Response::SharedPtr resp)
463465
{
464466
// reset success flag
465-
command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
467+
std::ignore = command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
466468
// call the service in the hardware
467-
command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_CMD].set_value(1.0);
469+
std::ignore = command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_CMD].set_value(1.0);
468470

469471
if (!waitForAsyncCommand(
470472
[&]() { return command_interfaces_[CommandInterfaces::RESEND_ROBOT_PROGRAM_ASYNC_SUCCESS].get_value(); })) {
@@ -488,9 +490,9 @@ bool GPIOController::handBackControl(std_srvs::srv::Trigger::Request::SharedPtr
488490
std_srvs::srv::Trigger::Response::SharedPtr resp)
489491
{
490492
// reset success flag
491-
command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
493+
std::ignore = command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
492494
// call the service in the hardware
493-
command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_CMD].set_value(1.0);
495+
std::ignore = command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_CMD].set_value(1.0);
494496

495497
if (!waitForAsyncCommand(
496498
[&]() { return command_interfaces_[CommandInterfaces::HAND_BACK_CONTROL_ASYNC_SUCCESS].get_value(); })) {
@@ -514,12 +516,12 @@ bool GPIOController::setPayload(const ur_msgs::srv::SetPayload::Request::SharedP
514516
ur_msgs::srv::SetPayload::Response::SharedPtr resp)
515517
{
516518
// reset success flag
517-
command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
519+
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
518520

519-
command_interfaces_[CommandInterfaces::PAYLOAD_MASS].set_value(req->mass);
520-
command_interfaces_[CommandInterfaces::PAYLOAD_COG_X].set_value(req->center_of_gravity.x);
521-
command_interfaces_[CommandInterfaces::PAYLOAD_COG_Y].set_value(req->center_of_gravity.y);
522-
command_interfaces_[CommandInterfaces::PAYLOAD_COG_Z].set_value(req->center_of_gravity.z);
521+
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_MASS].set_value(req->mass);
522+
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_X].set_value(req->center_of_gravity.x);
523+
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_Y].set_value(req->center_of_gravity.y);
524+
std::ignore = command_interfaces_[CommandInterfaces::PAYLOAD_COG_Z].set_value(req->center_of_gravity.z);
523525

524526
if (!waitForAsyncCommand(
525527
[&]() { return command_interfaces_[CommandInterfaces::PAYLOAD_ASYNC_SUCCESS].get_value(); })) {
@@ -543,9 +545,9 @@ bool GPIOController::zeroFTSensor(std_srvs::srv::Trigger::Request::SharedPtr /*r
543545
std_srvs::srv::Trigger::Response::SharedPtr resp)
544546
{
545547
// reset success flag
546-
command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
548+
std::ignore = command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_ASYNC_SUCCESS].set_value(ASYNC_WAITING);
547549
// call the service in the hardware
548-
command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_CMD].set_value(1.0);
550+
std::ignore = command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_CMD].set_value(1.0);
549551

550552
if (!waitForAsyncCommand(
551553
[&]() { return command_interfaces_[CommandInterfaces::ZERO_FTSENSOR_ASYNC_SUCCESS].get_value(); })) {

0 commit comments

Comments
 (0)