14 case Type::beep:
return QCoreApplication::translate(
"ActuatorAction",
"Beep");
15 case Type::set3DModeOn:
return QCoreApplication::translate(
"ActuatorAction",
"3D mode: On");
16 case Type::set3DModeOff:
return QCoreApplication::translate(
"ActuatorAction",
"3D mode: Off");
17 case Type::setSpinDirection1:
return QCoreApplication::translate(
"ActuatorAction",
"Set Spin Direction 1");
18 case Type::setSpinDirection2:
return QCoreApplication::translate(
"ActuatorAction",
"Set Spin Direction 2");
28 : _label(label), _outputFunction(outputFunction), _type(action.type), _vehicle(vehicle)
34 if (_commandInProgress) {
43 action->ackHandler(
static_cast<MAV_RESULT
>(ack.result), failureCode);
48 _commandInProgress =
false;
54void Action::sendMavlinkRequest()
56 qCDebug(ActuatorActionsLog) <<
"Sending actuator action, function:" << _outputFunction <<
"type:" << (int)_type;
60 handlerInfo.resultHandlerData =
this;
64 MAV_COMP_ID_AUTOPILOT1,
65 MAV_CMD_CONFIGURE_ACTUATOR,
73 _commandInProgress =
true;
77 : _label(label), _type(type)
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
ActionGroup(QObject *parent, const QString &label, Config::Type type)
Action(QObject *parent, const Config &action, const QString &label, int outputFunction, Vehicle *vehicle)
Q_INVOKABLE void trigger()
void sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Sends the command and calls the callback with the result.
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
MavCmdResultFailureCode_t
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.