Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
153 changes: 73 additions & 80 deletions src/Vehicle/StandardModes.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,91 +4,86 @@

QGC_LOGGING_CATEGORY(StandardModesLog, "Vehicle.StandardModes")

static void requestMessageResultHandler(void *resultHandlerData, MAV_RESULT result,
[[maybe_unused]] Vehicle::RequestMessageResultHandlerFailureCode_t failureCode,
const mavlink_message_t &message)
static void commandResultHandler(void *resultHandlerData, [[maybe_unused]] int compId,
const mavlink_command_ack_t &ack,
[[maybe_unused]] Vehicle::MavCmdResultFailureCode_t failureCode)
{
StandardModes* standardModes = static_cast<StandardModes*>(resultHandlerData);
standardModes->gotMessage(result, message);
if (ack.result != MAV_RESULT_ACCEPTED) {
qCDebug(StandardModesLog) << "Failed to request available modes - MAV_RESULT" << ack.result;
emit standardModes->requestCompleted();
}
}

StandardModes::StandardModes(QObject *parent, Vehicle *vehicle)
: QObject(parent), _vehicle(vehicle)
{
}

void StandardModes::gotMessage(MAV_RESULT result, const mavlink_message_t &message)
void StandardModes::availableModesReceived(const mavlink_message_t &message)
{
_requestActive = false;
if (_wantReset) {
_wantReset = false;
request();
return;
mavlink_available_modes_t availableModes;
mavlink_msg_available_modes_decode(&message, &availableModes);
bool cannotBeSet = availableModes.properties & MAV_MODE_PROPERTY_NOT_USER_SELECTABLE;
bool advanced = availableModes.properties & MAV_MODE_PROPERTY_ADVANCED;
availableModes.mode_name[sizeof(availableModes.mode_name)-1] = '\0';
QString name = availableModes.mode_name;
switch (availableModes.standard_mode) {
case MAV_STANDARD_MODE_POSITION_HOLD:
name = "Position";
break;
case MAV_STANDARD_MODE_ORBIT:
name = "Orbit";
cannotBeSet = true; // These are exposed in the UI as separate buttons
break;
case MAV_STANDARD_MODE_CRUISE:
name = "Cruise";
break;
case MAV_STANDARD_MODE_ALTITUDE_HOLD:
name = "Altitude";
break;
case MAV_STANDARD_MODE_SAFE_RECOVERY:
name = "Safe Recovery";
break;
case MAV_STANDARD_MODE_MISSION:
name = "Mission";
break;
case MAV_STANDARD_MODE_LAND:
name = "Land";
break;
case MAV_STANDARD_MODE_TAKEOFF:
name = "Takeoff";
break;
}

if (result == MAV_RESULT_ACCEPTED) {
mavlink_available_modes_t availableModes;
mavlink_msg_available_modes_decode(&message, &availableModes);
bool cannotBeSet = availableModes.properties & MAV_MODE_PROPERTY_NOT_USER_SELECTABLE;
bool advanced = availableModes.properties & MAV_MODE_PROPERTY_ADVANCED;
availableModes.mode_name[sizeof(availableModes.mode_name)-1] = '\0';
QString name = availableModes.mode_name;
switch (availableModes.standard_mode) {
case MAV_STANDARD_MODE_POSITION_HOLD:
name = "Position";
break;
case MAV_STANDARD_MODE_ORBIT:
name = "Orbit";
cannotBeSet = true; // These are exposed in the UI as separate buttons
break;
case MAV_STANDARD_MODE_CRUISE:
name = "Cruise";
break;
case MAV_STANDARD_MODE_ALTITUDE_HOLD:
name = "Altitude";
break;
case MAV_STANDARD_MODE_SAFE_RECOVERY:
name = "Safe Recovery";
break;
case MAV_STANDARD_MODE_MISSION:
name = "Mission";
break;
case MAV_STANDARD_MODE_LAND:
name = "Land";
break;
case MAV_STANDARD_MODE_TAKEOFF:
name = "Takeoff";
break;
}

qCDebug(StandardModesLog) << "Available mode received - name:" << name <<
"index:" << availableModes.mode_index <<
"standard_mode:" << availableModes.standard_mode <<
"advanced:" << advanced <<
"cannotBeSet:" << cannotBeSet <<
"custom_mode:" << availableModes.custom_mode;
qCDebug(StandardModesLog) << "Available mode received - name:" << name <<
"index:" << availableModes.mode_index <<
"standard_mode:" << availableModes.standard_mode <<
"advanced:" << advanced <<
"cannotBeSet:" << cannotBeSet <<
"custom_mode:" << availableModes.custom_mode;

_modeList += FirmwareFlightMode{
name,
availableModes.standard_mode,
availableModes.custom_mode,
!cannotBeSet,
advanced,
true, // fixed wing - Since we don't know at this point we assume fixed wing support
true // multi-rotor - Since we don't know at this point we assume multi-rotor support as well
};
_modeList += FirmwareFlightMode{
name,
availableModes.standard_mode,
availableModes.custom_mode,
!cannotBeSet,
advanced,
true, // fixed wing - Since we don't know at this point we assume fixed wing support
true // multi-rotor - Since we don't know at this point we assume multi-rotor support as well
};

if (availableModes.mode_index >= availableModes.number_modes) { // We are done
qCDebug(StandardModesLog) << "Completed, num modes:" << availableModes.number_modes;
ensureUniqueModeNames();
_vehicle->firmwarePlugin()->updateAvailableFlightModes(_modeList);
emit modesUpdated();
emit requestCompleted();
} else {
requestMode(availableModes.mode_index + 1);
if (availableModes.mode_index >= availableModes.number_modes) { // We are done
_requestActive = false;
if (_wantReset) {
_wantReset = false;
request();
return;
}
} else {
qCDebug(StandardModesLog) << "Failed to retrieve available modes - REQUEST_MESSAGE:MAV_RESULT" << result;
qCDebug(StandardModesLog) << "Completed, num modes:" << availableModes.number_modes;
ensureUniqueModeNames();
_vehicle->firmwarePlugin()->updateAvailableFlightModes(_modeList);
emit modesUpdated();
emit requestCompleted();
}
}
Expand Down Expand Up @@ -117,19 +112,17 @@ void StandardModes::request()
}

qCDebug(StandardModesLog) << "Requesting available modes";
// Request one at a time. This could be improved by requesting all, but we can't use Vehicle::requestMessage for that
_modeList.clear();
StandardModes::requestMode(1);
}

void StandardModes::requestMode(int modeIndex)
{
_requestActive = true;
_vehicle->requestMessage(
requestMessageResultHandler,
this,
Vehicle::MavCmdAckHandlerInfo_t handlerInfo{};
handlerInfo.resultHandler = commandResultHandler;
handlerInfo.resultHandlerData = this;
_vehicle->sendMavCommandWithHandler(
&handlerInfo,
MAV_COMP_ID_AUTOPILOT1,
MAVLINK_MSG_ID_AVAILABLE_MODES, modeIndex);
MAV_CMD_REQUEST_MESSAGE,
MAVLINK_MSG_ID_AVAILABLE_MODES,
0); // param2=0: request all modes at once
}

void StandardModes::availableModesMonitorReceived(uint8_t seq)
Expand Down
4 changes: 1 addition & 3 deletions src/Vehicle/StandardModes.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,13 @@ Q_OBJECT

void availableModesMonitorReceived(uint8_t seq);

void gotMessage(MAV_RESULT result, const mavlink_message_t &message);
void availableModesReceived(const mavlink_message_t &message);

signals:
void modesUpdated();
void requestCompleted();

private:

void requestMode(int modeIndex);
void ensureUniqueModeNames();

Vehicle*const _vehicle;
Expand Down
3 changes: 3 additions & 0 deletions src/Vehicle/Vehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -692,6 +692,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
}
}
break;
case MAVLINK_MSG_ID_AVAILABLE_MODES:
_standardModes->availableModesReceived(message);
break;
case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
{
Expand Down
Loading