Unverified Commit f39452b3 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7084 from DonLakeFlyer/Orbit

Orbit: Show center point telemetry and flight mode
parents 151ce31f b4d3e248
......@@ -36,23 +36,24 @@ PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent)
}
PX4FirmwarePlugin::PX4FirmwarePlugin(void)
: _manualFlightMode(tr("Manual"))
, _acroFlightMode(tr("Acro"))
, _stabilizedFlightMode(tr("Stabilized"))
, _rattitudeFlightMode(tr("Rattitude"))
, _altCtlFlightMode(tr("Altitude"))
, _posCtlFlightMode(tr("Position"))
, _offboardFlightMode(tr("Offboard"))
, _readyFlightMode(tr("Ready"))
, _takeoffFlightMode(tr("Takeoff"))
, _holdFlightMode(tr("Hold"))
, _missionFlightMode(tr("Mission"))
, _rtlFlightMode(tr("Return"))
, _landingFlightMode(tr("Land"))
, _preclandFlightMode(tr("Precision Land"))
, _rtgsFlightMode(tr("Return to Groundstation"))
, _followMeFlightMode(tr("Follow Me"))
, _simpleFlightMode(tr("Simple"))
: _manualFlightMode (tr("Manual"))
, _acroFlightMode (tr("Acro"))
, _stabilizedFlightMode (tr("Stabilized"))
, _rattitudeFlightMode (tr("Rattitude"))
, _altCtlFlightMode (tr("Altitude"))
, _posCtlFlightMode (tr("Position"))
, _offboardFlightMode (tr("Offboard"))
, _readyFlightMode (tr("Ready"))
, _takeoffFlightMode (tr("Takeoff"))
, _holdFlightMode (tr("Hold"))
, _missionFlightMode (tr("Mission"))
, _rtlFlightMode (tr("Return"))
, _landingFlightMode (tr("Land"))
, _preclandFlightMode (tr("Precision Land"))
, _rtgsFlightMode (tr("Return to Groundstation"))
, _followMeFlightMode (tr("Follow Me"))
, _simpleFlightMode (tr("Simple"))
, _orbitFlightMode (tr("Orbit"))
{
qmlRegisterType<PX4AdvancedFlightModesController> ("QGroundControl.Controllers", 1, 0, "PX4AdvancedFlightModesController");
qmlRegisterType<PX4SimpleFlightModesController> ("QGroundControl.Controllers", 1, 0, "PX4SimpleFlightModesController");
......@@ -76,15 +77,14 @@ PX4FirmwarePlugin::PX4FirmwarePlugin(void)
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_POSCTL, 0, true, true, true },
// simple can't be set by the user right now
{ PX4_CUSTOM_MAIN_MODE_SIMPLE, 0, false, false, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_SIMPLE, 0, false, false, true },
{ PX4_CUSTOM_MAIN_MODE_POSCTL, PX4_CUSTOM_SUB_MODE_POSCTL_POSCTL, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_POSCTL, PX4_CUSTOM_SUB_MODE_POSCTL_ORBIT, false, false, false },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, true, false, true },
// modes that can't be directly set by the user
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND, false, false, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_READY, false, true, true },
......@@ -99,13 +99,14 @@ PX4FirmwarePlugin::PX4FirmwarePlugin(void)
&_acroFlightMode,
&_rattitudeFlightMode,
&_altCtlFlightMode,
&_posCtlFlightMode,
&_offboardFlightMode,
&_simpleFlightMode,
&_posCtlFlightMode,
&_orbitFlightMode,
&_holdFlightMode,
&_missionFlightMode,
&_rtlFlightMode,
&_followMeFlightMode,
&_offboardFlightMode,
&_landingFlightMode,
&_preclandFlightMode,
&_readyFlightMode,
......
......@@ -105,6 +105,7 @@ protected:
QString _rtgsFlightMode;
QString _followMeFlightMode;
QString _simpleFlightMode;
QString _orbitFlightMode;
private slots:
void _mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
......
......@@ -34,7 +34,7 @@
/**
* @file px4_custom_mode.h
* PX4 custom flight modes
* Copied from PX4 2018-04-07 - https://github.com/PX4/Firmware/blob/master/src/modules/commander/px4_custom_mode.h#L45
*
*/
#ifndef PX4_CUSTOM_MODE_H_
......@@ -66,18 +66,23 @@ enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND
};
enum PX4_CUSTOM_SUB_MODE_POSCTL {
PX4_CUSTOM_SUB_MODE_POSCTL_POSCTL = 0,
PX4_CUSTOM_SUB_MODE_POSCTL_ORBIT
};
union px4_custom_mode {
struct {
uint16_t reserved;
uint8_t main_mode;
uint8_t sub_mode;
};
struct {
uint16_t reserved_hl;
uint16_t custom_mode_hl;
};
uint32_t data;
uint32_t data;
float data_float;
struct {
uint16_t reserved_hl;
uint16_t custom_mode_hl;
};
};
#endif /* PX4_CUSTOM_MODE_H_ */
......@@ -318,6 +318,8 @@ FlightMap {
}
}
// Orbit visuals
QGCMapCircleVisuals {
id: orbitMapCircle
mapControl: parent
......@@ -354,13 +356,29 @@ FlightMap {
}
}
// Used to show orbit status telemetry from the vehicle
// Orbit telemetry visuals
QGCMapCircleVisuals {
id: orbitTelemetryCircle
mapControl: parent
mapCircle: _activeVehicle ? _activeVehicle.orbitMapCircle : null
visible: _activeVehicle ? _activeVehicle.orbitActive : false
}
MapQuickItem {
id: orbitCenterIndicator
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
coordinate: _activeVehicle ? _activeVehicle.orbitMapCircle.center : undefined
visible: orbitTelemetryCircle.visible
sourceItem: MissionItemIndexLabel {
checked: true
index: -1
label: qsTr("Orbit", "Orbit waypoint")
}
}
// Handle guided mode clicks
MouseArea {
anchors.fill: parent
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment