@@ -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