9 case Type::beep:
return QCoreApplication::translate(
"ActuatorAction",
"Beep");
10 case Type::set3DModeOn:
return QCoreApplication::translate(
"ActuatorAction",
"3D mode: On");
11 case Type::set3DModeOff:
return QCoreApplication::translate(
"ActuatorAction",
"3D mode: Off");
23 : _label(label), _outputFunction(outputFunction), _type(action.type), _vehicle(vehicle)
29 if (_commandInProgress) {
38 action->ackHandler(
static_cast<MAV_RESULT
>(ack.result), failureCode);
43 _commandInProgress =
false;
45 qgcApp()->showAppMessage(tr(
"Actuator action command failed"));
49void Action::sendMavlinkRequest()
51 qCDebug(ActuatorsConfigLog) <<
"Sending actuator action, function:" << _outputFunction <<
"type:" << (int)_type;
55 handlerInfo.resultHandlerData =
this;
59 MAV_COMP_ID_AUTOPILOT1,
60 MAV_CMD_CONFIGURE_ACTUATOR,
68 _commandInProgress =
true;
72 : _label(label), _type(type)
ActionGroup(QObject *parent, const QString &label, Config::Type type)
Action(QObject *parent, const Config &action, const QString &label, int outputFunction, Vehicle *vehicle)
MavCmdResultFailureCode_t
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
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.
@ set3DModeOn
motors: enable 3D mode (reversible)
@ setSpinDirection2
motors: set spin direction 2
@ set3DModeOff
motors: disable 3D mode (reversible)
@ setSpinDirection1
motors: set spin direction 1
QString typeToLabel() const
MavCmdResultHandler resultHandler