Unverified Commit e4b7eb1c authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #8109 from mavlink/pr-roi

ROI for manual flight
parents 7d592840 8ea27d19
...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 4.0.0 - Daily Build ### 4.0.0 - Daily Build
* Added ROI option during manual flight.
* Windows: Move builds to 64 bit, Qt 5.12.5 * Windows: Move builds to 64 bit, Qt 5.12.5
* Plan: ROI button will switch to Cancel ROI at appropriate times * Plan: ROI button will switch to Cancel ROI at appropriate times
* Plan: When ROI is selected the flight path lines which are affected by the ROI will change color * Plan: When ROI is selected the flight path lines which are affected by the ROI will change color
......
...@@ -131,9 +131,9 @@ AndroidBuild { ...@@ -131,9 +131,9 @@ AndroidBuild {
contains(DEFINES, QGC_ENABLE_PAIRING) { contains(DEFINES, QGC_ENABLE_PAIRING) {
MacBuild { MacBuild {
#- Pairing is generally not supported on macOS. This is here solely for development. #- Pairing is generally not supported on macOS. This is here solely for development.
exists(/usr/local/Cellar/openssl/1.0.2s/include) { exists(/usr/local/Cellar/openssl/1.0.2t/include) {
INCLUDEPATH += /usr/local/Cellar/openssl/1.0.2s/include INCLUDEPATH += /usr/local/Cellar/openssl/1.0.2t/include
LIBS += -L/usr/local/Cellar/openssl/1.0.2s/lib LIBS += -L/usr/local/Cellar/openssl/1.0.2t/lib
LIBS += -lcrypto -lz LIBS += -lcrypto -lz
} else { } else {
# There is some circular reference settings going on between QGCExternalLibs.pri and gqgroundcontrol.pro. # There is some circular reference settings going on between QGCExternalLibs.pri and gqgroundcontrol.pro.
......
...@@ -147,6 +147,7 @@ ...@@ -147,6 +147,7 @@
<file alias="RCLossLight.svg">src/AutoPilotPlugins/PX4/Images/RCLossLight.svg</file> <file alias="RCLossLight.svg">src/AutoPilotPlugins/PX4/Images/RCLossLight.svg</file>
<file alias="ReturnToHomeAltitude.svg">src/AutoPilotPlugins/PX4/Images/ReturnToHomeAltitude.svg</file> <file alias="ReturnToHomeAltitude.svg">src/AutoPilotPlugins/PX4/Images/ReturnToHomeAltitude.svg</file>
<file alias="ReturnToHomeAltitudeCopter.svg">src/AutoPilotPlugins/PX4/Images/ReturnToHomeAltitudeCopter.svg</file> <file alias="ReturnToHomeAltitudeCopter.svg">src/AutoPilotPlugins/PX4/Images/ReturnToHomeAltitudeCopter.svg</file>
<file alias="roi.svg">src/ui/toolbar/Images/roi.svg</file>
<file alias="rollDialWhite.svg">src/FlightMap/Images/rollDialWhite.svg</file> <file alias="rollDialWhite.svg">src/FlightMap/Images/rollDialWhite.svg</file>
<file alias="rollPointerWhite.svg">src/FlightMap/Images/rollPointerWhite.svg</file> <file alias="rollPointerWhite.svg">src/FlightMap/Images/rollPointerWhite.svg</file>
<file alias="RTK.svg">src/ui/toolbar/Images/RTK.svg</file> <file alias="RTK.svg">src/ui/toolbar/Images/RTK.svg</file>
......
...@@ -15,6 +15,7 @@ ...@@ -15,6 +15,7 @@
<file alias="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file> <file alias="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file>
<file alias="MultiVehicleSelector.qml">src/ui/toolbar/MultiVehicleSelector.qml</file> <file alias="MultiVehicleSelector.qml">src/ui/toolbar/MultiVehicleSelector.qml</file>
<file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file> <file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file>
<file alias="ROIIndicator.qml">src/ui/toolbar/ROIIndicator.qml</file>
<file alias="TelemetryRSSIIndicator.qml">src/ui/toolbar/TelemetryRSSIIndicator.qml</file> <file alias="TelemetryRSSIIndicator.qml">src/ui/toolbar/TelemetryRSSIIndicator.qml</file>
<file alias="VTOLModeIndicator.qml">src/ui/toolbar/VTOLModeIndicator.qml</file> <file alias="VTOLModeIndicator.qml">src/ui/toolbar/VTOLModeIndicator.qml</file>
</qresource> </qresource>
......
...@@ -271,18 +271,15 @@ void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordina ...@@ -271,18 +271,15 @@ void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordina
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
} }
void FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel) void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double)
{ {
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(vehicle);
Q_UNUSED(altitudeRel);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
} }
void FirmwarePlugin::startMission(Vehicle* vehicle) void FirmwarePlugin::startMission(Vehicle*)
{ {
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(vehicle);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
} }
...@@ -293,33 +290,28 @@ const FirmwarePlugin::remapParamNameMajorVersionMap_t& FirmwarePlugin::paramName ...@@ -293,33 +290,28 @@ const FirmwarePlugin::remapParamNameMajorVersionMap_t& FirmwarePlugin::paramName
return remap; return remap;
} }
int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int) const
{ {
Q_UNUSED(majorVersionNumber);
return 0; return 0;
} }
QString FirmwarePlugin::vehicleImageOpaque(const Vehicle* vehicle) const QString FirmwarePlugin::vehicleImageOpaque(const Vehicle*) const
{ {
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg"); return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg");
} }
QString FirmwarePlugin::vehicleImageOutline(const Vehicle* vehicle) const QString FirmwarePlugin::vehicleImageOutline(const Vehicle*) const
{ {
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/vehicleArrowOutline.svg"); return QStringLiteral("/qmlimages/vehicleArrowOutline.svg");
} }
QString FirmwarePlugin::vehicleImageCompass(const Vehicle* vehicle) const QString FirmwarePlugin::vehicleImageCompass(const Vehicle*) const
{ {
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/compassInstrumentArrow.svg"); return QStringLiteral("/qmlimages/compassInstrumentArrow.svg");
} }
const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle) const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle*)
{ {
Q_UNUSED(vehicle);
//-- Default list of indicators for all vehicles. //-- Default list of indicators for all vehicles.
if(_toolBarIndicatorList.size() == 0) { if(_toolBarIndicatorList.size() == 0) {
_toolBarIndicatorList = QVariantList({ _toolBarIndicatorList = QVariantList({
...@@ -329,6 +321,7 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle) ...@@ -329,6 +321,7 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle)
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ROIIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")),
...@@ -339,10 +332,8 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle) ...@@ -339,10 +332,8 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle)
return _toolBarIndicatorList; return _toolBarIndicatorList;
} }
const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) const QVariantList& FirmwarePlugin::cameraList(const Vehicle*)
{ {
Q_UNUSED(vehicle);
if (_cameraList.size() == 0) { if (_cameraList.size() == 0) {
CameraMetaData* metaData; CameraMetaData* metaData;
......
...@@ -48,6 +48,7 @@ public: ...@@ -48,6 +48,7 @@ public:
GuidedModeCapability = 1 << 2, ///< Vehicle supports guided mode commands GuidedModeCapability = 1 << 2, ///< Vehicle supports guided mode commands
OrbitModeCapability = 1 << 3, ///< Vehicle supports orbit mode OrbitModeCapability = 1 << 3, ///< Vehicle supports orbit mode
TakeoffVehicleCapability = 1 << 4, ///< Vehicle supports guided takeoff TakeoffVehicleCapability = 1 << 4, ///< Vehicle supports guided takeoff
ROIModeCapability = 1 << 5, ///< Vehicle supports ROI
} FirmwareCapabilities; } FirmwareCapabilities;
/// Maps from on parameter name to another /// Maps from on parameter name to another
......
...@@ -226,10 +226,13 @@ bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_m ...@@ -226,10 +226,13 @@ bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_m
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
{ {
int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability; int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
//-- This is arbitrary until I find how to really tell if ROI is avaiable
if (vehicle->multiRotor()) {
available |= ROIModeCapability;
}
if (vehicle->multiRotor() || vehicle->vtol()) { if (vehicle->multiRotor() || vehicle->vtol()) {
available |= TakeoffVehicleCapability | OrbitModeCapability; available |= TakeoffVehicleCapability | OrbitModeCapability;
} }
return (capabilities & available) == capabilities; return (capabilities & available) == capabilities;
} }
......
...@@ -44,7 +44,6 @@ FlightMap { ...@@ -44,7 +44,6 @@ FlightMap {
property var _geoFenceController: missionController.geoFenceController property var _geoFenceController: missionController.geoFenceController
property var _rallyPointController: missionController.rallyPointController property var _rallyPointController: missionController.rallyPointController
property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: activeVehicle ? activeVehicle.coordinate : QtPositioning.coordinate() property var _activeVehicleCoordinate: activeVehicle ? activeVehicle.coordinate : QtPositioning.coordinate()
property real _toolButtonTopMargin: parent.height - mainWindow.height + (ScreenTools.defaultFontPixelHeight / 2) property real _toolButtonTopMargin: parent.height - mainWindow.height + (ScreenTools.defaultFontPixelHeight / 2)
property bool _airspaceEnabled: QGroundControl.airmapSupported ? (QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue && QGroundControl.airspaceManager.connected): false property bool _airspaceEnabled: QGroundControl.airmapSupported ? (QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue && QGroundControl.airspaceManager.connected): false
...@@ -409,6 +408,34 @@ FlightMap { ...@@ -409,6 +408,34 @@ FlightMap {
} }
} }
// ROI Location visuals
MapQuickItem {
id: roiLocationItem
visible: activeVehicle && activeVehicle.isROIEnabled
z: QGroundControl.zOrderMapItems
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
sourceItem: MissionItemIndexLabel {
checked: true
index: -1
label: qsTr("ROI here", "Make this a Region Of Interest")
}
//-- Visibilty controlled by actual state
function show(coord) {
roiLocationItem.coordinate = coord
}
function hide() {
}
function actionConfirmed() {
}
function actionCancelled() {
}
}
// Orbit telemetry visuals // Orbit telemetry visuals
QGCMapCircleVisuals { QGCMapCircleVisuals {
id: orbitTelemetryCircle id: orbitTelemetryCircle
...@@ -437,9 +464,7 @@ FlightMap { ...@@ -437,9 +464,7 @@ FlightMap {
QGCMenu { QGCMenu {
id: clickMenu id: clickMenu
property var coord property var coord
QGCMenuItem { QGCMenuItem {
text: qsTr("Go to location") text: qsTr("Go to location")
visible: guidedActionsController.showGotoLocation visible: guidedActionsController.showGotoLocation
...@@ -450,7 +475,6 @@ FlightMap { ...@@ -450,7 +475,6 @@ FlightMap {
guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickMenu.coord, gotoLocationItem) guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickMenu.coord, gotoLocationItem)
} }
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Orbit at location") text: qsTr("Orbit at location")
visible: guidedActionsController.showOrbit visible: guidedActionsController.showOrbit
...@@ -461,6 +485,15 @@ FlightMap { ...@@ -461,6 +485,15 @@ FlightMap {
guidedActionsController.confirmAction(guidedActionsController.actionOrbit, clickMenu.coord, orbitMapCircle) guidedActionsController.confirmAction(guidedActionsController.actionOrbit, clickMenu.coord, orbitMapCircle)
} }
} }
QGCMenuItem {
text: qsTr("ROI at location")
visible: guidedActionsController.showROI
onTriggered: {
roiLocationItem.show(clickMenu.coord)
guidedActionsController.confirmAction(guidedActionsController.actionROI, clickMenu.coord, orbitMapCircle)
}
}
} }
onClicked: { onClicked: {
......
...@@ -2979,6 +2979,11 @@ bool Vehicle::orbitModeSupported() const ...@@ -2979,6 +2979,11 @@ bool Vehicle::orbitModeSupported() const
return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability); return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability);
} }
bool Vehicle::roiModeSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::ROIModeCapability);
}
bool Vehicle::takeoffVehicleSupported() const bool Vehicle::takeoffVehicleSupported() const
{ {
return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability); return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
...@@ -3084,6 +3089,74 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, ...@@ -3084,6 +3089,74 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
} }
} }
void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord)
{
if (!roiModeSupported()) {
qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle."));
return;
}
if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
sendMavCommandInt(
defaultComponentId(),
MAV_CMD_DO_SET_ROI_LOCATION,
MAV_FRAME_GLOBAL,
true, // show error if fails
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
centerCoord.latitude(),
centerCoord.longitude(),
static_cast<float>(centerCoord.altitude()));
} else {
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_SET_ROI_LOCATION,
true, // show error if fails
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(centerCoord.latitude()),
static_cast<float>(centerCoord.longitude()),
static_cast<float>(centerCoord.altitude()));
}
}
void Vehicle::stopGuidedModeROI()
{
if (!roiModeSupported()) {
qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle."));
return;
}
if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
sendMavCommandInt(
defaultComponentId(),
MAV_CMD_DO_SET_ROI_NONE,
MAV_FRAME_GLOBAL,
true, // show error if fails
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<double>(qQNaN()), // Empty
static_cast<double>(qQNaN()), // Empty
static_cast<float>(qQNaN())); // Empty
} else {
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_SET_ROI_NONE,
true, // show error if fails
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN()), // Empty
static_cast<float>(qQNaN())); // Empty
}
}
void Vehicle::pauseVehicle(void) void Vehicle::pauseVehicle(void)
{ {
if (!pauseVehicleSupported()) { if (!pauseVehicleSupported()) {
...@@ -3352,6 +3425,20 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) ...@@ -3352,6 +3425,20 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
} }
} }
if (ack.command == MAV_CMD_DO_SET_ROI_LOCATION) {
if (ack.result == MAV_RESULT_ACCEPTED) {
_isROIEnabled = true;
emit isROIEnabledChanged();
}
}
if (ack.command == MAV_CMD_DO_SET_ROI_NONE) {
if (ack.result == MAV_RESULT_ACCEPTED) {
_isROIEnabled = false;
emit isROIEnabledChanged();
}
}
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) { if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
qgcApp()->showMessage(tr("Bootloader flash succeeded")); qgcApp()->showMessage(tr("Bootloader flash succeeded"));
......
...@@ -634,6 +634,7 @@ public: ...@@ -634,6 +634,7 @@ public:
Q_PROPERTY(qreal gimbalPitch READ gimbalPitch NOTIFY gimbalPitchChanged) Q_PROPERTY(qreal gimbalPitch READ gimbalPitch NOTIFY gimbalPitchChanged)
Q_PROPERTY(qreal gimbalYaw READ gimbalYaw NOTIFY gimbalYawChanged) Q_PROPERTY(qreal gimbalYaw READ gimbalYaw NOTIFY gimbalYawChanged)
Q_PROPERTY(bool gimbalData READ gimbalData NOTIFY gimbalDataChanged) Q_PROPERTY(bool gimbalData READ gimbalData NOTIFY gimbalDataChanged)
Q_PROPERTY(bool isROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged)
// The following properties relate to Orbit status // The following properties relate to Orbit status
Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged) Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
...@@ -646,6 +647,7 @@ public: ...@@ -646,6 +647,7 @@ public:
Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool roiModeSupported READ roiModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT) ///< Flight mode vehicle is in while performing goto Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT) ///< Flight mode vehicle is in while performing goto
...@@ -729,6 +731,11 @@ public: ...@@ -729,6 +731,11 @@ public:
/// @param amslAltitude Desired vehicle altitude /// @param amslAltitude Desired vehicle altitude
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude); Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
/// Command vehicle to keep given point as ROI
/// @param centerCoord ROI coordinates
Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
Q_INVOKABLE void stopGuidedModeROI();
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left /// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause. /// in guided mode after pause.
Q_INVOKABLE void pauseVehicle(void); Q_INVOKABLE void pauseVehicle(void);
...@@ -778,6 +785,7 @@ public: ...@@ -778,6 +785,7 @@ public:
bool guidedModeSupported (void) const; bool guidedModeSupported (void) const;
bool pauseVehicleSupported (void) const; bool pauseVehicleSupported (void) const;
bool orbitModeSupported (void) const; bool orbitModeSupported (void) const;
bool roiModeSupported (void) const;
bool takeoffVehicleSupported (void) const; bool takeoffVehicleSupported (void) const;
QString gotoFlightMode (void) const; QString gotoFlightMode (void) const;
...@@ -1100,6 +1108,7 @@ public: ...@@ -1100,6 +1108,7 @@ public:
qreal gimbalPitch () { return static_cast<qreal>(_curGimbalPitch); } qreal gimbalPitch () { return static_cast<qreal>(_curGimbalPitch); }
qreal gimbalYaw () { return static_cast<qreal>(_curGinmbalYaw); } qreal gimbalYaw () { return static_cast<qreal>(_curGinmbalYaw); }
bool gimbalData () { return _haveGimbalData; } bool gimbalData () { return _haveGimbalData; }
bool isROIEnabled () { return _isROIEnabled; }
public slots: public slots:
void setVtolInFwdFlight (bool vtolInFwdFlight); void setVtolInFwdFlight (bool vtolInFwdFlight);
...@@ -1215,6 +1224,7 @@ signals: ...@@ -1215,6 +1224,7 @@ signals:
void gimbalPitchChanged (); void gimbalPitchChanged ();
void gimbalYawChanged (); void gimbalYawChanged ();
void gimbalDataChanged (); void gimbalDataChanged ();
void isROIEnabledChanged ();
private slots: private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message); void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
...@@ -1481,6 +1491,7 @@ private: ...@@ -1481,6 +1491,7 @@ private:
float _curGimbalPitch = 0.0f; float _curGimbalPitch = 0.0f;
float _curGinmbalYaw = 0.0f; float _curGinmbalYaw = 0.0f;
bool _haveGimbalData = false; bool _haveGimbalData = false;
bool _isROIEnabled = false;
Joystick* _activeJoystick = nullptr; Joystick* _activeJoystick = nullptr;
int _firmwareMajorVersion; int _firmwareMajorVersion;
......
...@@ -49,6 +49,7 @@ public: ...@@ -49,6 +49,7 @@ public:
Q_PROPERTY(QString firmwareUpgradeSingleURL READ firmwareUpgradeSingleURL CONSTANT) Q_PROPERTY(QString firmwareUpgradeSingleURL READ firmwareUpgradeSingleURL CONSTANT)
Q_PROPERTY(bool guidedBarShowEmergencyStop READ guidedBarShowEmergencyStop NOTIFY guidedBarShowEmergencyStopChanged) Q_PROPERTY(bool guidedBarShowEmergencyStop READ guidedBarShowEmergencyStop NOTIFY guidedBarShowEmergencyStopChanged)
Q_PROPERTY(bool guidedBarShowOrbit READ guidedBarShowOrbit NOTIFY guidedBarShowOrbitChanged) Q_PROPERTY(bool guidedBarShowOrbit READ guidedBarShowOrbit NOTIFY guidedBarShowOrbitChanged)
Q_PROPERTY(bool guidedBarShowROI READ guidedBarShowROI NOTIFY guidedBarShowROIChanged)
Q_PROPERTY(bool missionWaypointsOnly READ missionWaypointsOnly NOTIFY missionWaypointsOnlyChanged) Q_PROPERTY(bool missionWaypointsOnly READ missionWaypointsOnly NOTIFY missionWaypointsOnlyChanged)
Q_PROPERTY(bool multiVehicleEnabled READ multiVehicleEnabled NOTIFY multiVehicleEnabledChanged) Q_PROPERTY(bool multiVehicleEnabled READ multiVehicleEnabled NOTIFY multiVehicleEnabledChanged)
Q_PROPERTY(bool showOfflineMapExport READ showOfflineMapExport NOTIFY showOfflineMapExportChanged) Q_PROPERTY(bool showOfflineMapExport READ showOfflineMapExport NOTIFY showOfflineMapExportChanged)
...@@ -110,6 +111,7 @@ public: ...@@ -110,6 +111,7 @@ public:
virtual bool showFirmwareUpgrade () const { return true; } virtual bool showFirmwareUpgrade () const { return true; }
virtual bool guidedBarShowEmergencyStop () const { return true; } virtual bool guidedBarShowEmergencyStop () const { return true; }
virtual bool guidedBarShowOrbit () const { return true; } virtual bool guidedBarShowOrbit () const { return true; }
virtual bool guidedBarShowROI () const { return true; }
virtual bool missionWaypointsOnly () const { return false; } ///< true: Only allow waypoints and complex items in Plan virtual bool missionWaypointsOnly () const { return false; } ///< true: Only allow waypoints and complex items in Plan
virtual bool multiVehicleEnabled () const { return true; } ///< false: multi vehicle support is disabled virtual bool multiVehicleEnabled () const { return true; } ///< false: multi vehicle support is disabled
virtual bool guidedActionsRequireRCRSSI () const { return false; } ///< true: Guided actions will be disabled is there is no RC RSSI virtual bool guidedActionsRequireRCRSSI () const { return false; } ///< true: Guided actions will be disabled is there is no RC RSSI
...@@ -147,6 +149,7 @@ signals: ...@@ -147,6 +149,7 @@ signals:
void showFirmwareUpgradeChanged (bool show); void showFirmwareUpgradeChanged (bool show);
void guidedBarShowEmergencyStopChanged (bool show); void guidedBarShowEmergencyStopChanged (bool show);
void guidedBarShowOrbitChanged (bool show); void guidedBarShowOrbitChanged (bool show);
void guidedBarShowROIChanged (bool show);
void missionWaypointsOnlyChanged (bool missionWaypointsOnly); void missionWaypointsOnlyChanged (bool missionWaypointsOnly);
void multiVehicleEnabledChanged (bool multiVehicleEnabled); void multiVehicleEnabledChanged (bool multiVehicleEnabled);
void showOfflineMapExportChanged (); void showOfflineMapExportChanged ();
......
...@@ -629,6 +629,12 @@ ApplicationWindow { ...@@ -629,6 +629,12 @@ ApplicationWindow {
indicatorDropdown.open() indicatorDropdown.open()
} }
function hidePopUp() {
indicatorDropdown.close()
indicatorDropdown.currentItem = null
indicatorDropdown.currentIndicator = null
}
Popup { Popup {
id: indicatorDropdown id: indicatorDropdown
y: ScreenTools.defaultFontPixelHeight y: ScreenTools.defaultFontPixelHeight
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 23.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 288" style="enable-background:new 0 0 288 288;" xml:space="preserve">
<path d="M188.3,144c0,24.5-19.8,44.3-44.3,44.3S99.7,168.5,99.7,144s19.8-44.3,44.3-44.3S188.3,119.5,188.3,144z M288,144
c0,6.1-5,11.1-11.1,11.1h-28.3c-5.2,49.2-44.4,88.4-93.6,93.6v28.3c0,6.1-5,11.1-11.1,11.1s-11.1-5-11.1-11.1v-28.3
c-49.2-5.2-88.4-44.4-93.6-93.6H11.1C5,155.1,0,150.1,0,144s5-11.1,11.1-11.1h28.3c5.2-49.2,44.4-88.4,93.6-93.6V11.1
C132.9,5,137.9,0,144,0s11.1,5,11.1,11.1v28.3c49.2,5.2,88.4,44.4,93.6,93.6h28.3C283,132.9,288,137.9,288,144z M227.1,144
c0-45.8-37.3-83.1-83.1-83.1S60.9,98.2,60.9,144s37.3,83.1,83.1,83.1S227.1,189.8,227.1,144z"/>
</svg>
/****************************************************************************
*
* (c) 2009-2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
* @file
* @author Gus Grubba <gus@auterion.com>
*/
import QtQuick 2.11
import QtQuick.Controls 1.4
import QtQuick.Layouts 1.11
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
//-------------------------------------------------------------------------
//-- ROI Indicator
Item {
id: _root
width: showIndicator ? roiIcon.width : 0
visible: showIndicator
anchors.top: parent.top
anchors.bottom: parent.bottom
property bool showIndicator: activeVehicle && activeVehicle.roiModeSupported
Component {
id: roiInfo
Rectangle {
width: roiCol.width + ScreenTools.defaultFontPixelWidth * 6
height: roiCol.height + ScreenTools.defaultFontPixelHeight * 2
radius: ScreenTools.defaultFontPixelHeight * 0.5
color: qgcPal.window
Column {
id: roiCol
spacing: ScreenTools.defaultFontPixelHeight * 0.5
width: Math.max(roiButton.width, roiLabel.width)
anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.centerIn: parent
QGCLabel {
id: roiLabel
text: qsTr("ROI Disabled")
font.family: ScreenTools.demiboldFontFamily
visible: !roiButton.visible
anchors.horizontalCenter: parent.horizontalCenter
}
QGCButton {
id: roiButton
visible: activeVehicle && activeVehicle.isROIEnabled
text: qsTr("Disable ROI")
onClicked: {
if(activeVehicle)
activeVehicle.stopGuidedModeROI()
mainWindow.hidePopUp()
}
}
}
}
}
QGCColoredImage {
id: roiIcon
width: height
anchors.top: parent.top
anchors.bottom: parent.bottom
sourceSize.height: height
source: "/qmlimages/roi.svg"
color: activeVehicle && activeVehicle.isROIEnabled ? qgcPal.colorGreen : qgcPal.text
fillMode: Image.PreserveAspectFit
opacity: activeVehicle && activeVehicle.isROIEnabled ? 1 : 0.5
}
MouseArea {
anchors.fill: parent
onClicked: {
mainWindow.showPopUp(_root, roiInfo)
}
}
}
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