Browse Source

Merge pull request #8450 from DonLakeFlyer/StableSync

Stable_V4.0 -> master sync
QGC4.4
Don Gagne 5 years ago committed by GitHub
parent
commit
04f925d488
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 3
      .travis.yml
  2. 8
      ChangeLog.md
  3. 2
      QGCInstaller.pri
  4. 7
      src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc
  5. 3
      src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h
  6. 9
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  7. 6
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
  8. 9
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
  9. 6
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h
  10. 34
      src/FlightDisplay/PreFlightCheckList.qml
  11. 23
      src/FlightMap/Widgets/MapFitFunctions.qml
  12. 1
      src/QmlControls/ToolStrip.qml
  13. 7
      src/Vehicle/Vehicle.cc
  14. 27
      src/VehicleSetup/FirmwareUpgradeController.cc

3
.travis.yml

@ -225,6 +225,7 @@ before_deploy:
deploy: deploy:
# deploy installers to s3 builds/ if on a branch # deploy installers to s3 builds/ if on a branch
- provider: s3 - provider: s3
edge: true # Use V2 provider to work around V1 bug
access_key_id: AKIAIVORNALE7NHD3T6Q access_key_id: AKIAIVORNALE7NHD3T6Q
secret_access_key: secret_access_key:
secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4= secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4=
@ -255,6 +256,7 @@ deploy:
# deploy tagged installers to s3 version folder # deploy tagged installers to s3 version folder
- provider: s3 - provider: s3
edge: true # Use V2 provider to work around V1 bug
access_key_id: AKIAIVORNALE7NHD3T6Q access_key_id: AKIAIVORNALE7NHD3T6Q
secret_access_key: secret_access_key:
secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4= secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4=
@ -270,6 +272,7 @@ deploy:
# deploy installers to Github releases if on a tag # deploy installers to Github releases if on a tag
- provider: releases - provider: releases
edge: true # Use V2 provider to work around V1 bug
api-key: api-key:
secure: K/Zqr/FCC7QvzFxYvBtCinPkacQq2ubJ2qm982+38Zf/KjibVOF1dEbVdrGZmII6Tg5DaQzNXGYkg5PvYmJgT9xRsqeQjeYIUYqYZpAt+HYWA38AVfMU8jip/1P1wmwqD469nzJOBBa8yfsMs6Ca7tBaNl/zTxCRGnAgEzqtkdQ= secure: K/Zqr/FCC7QvzFxYvBtCinPkacQq2ubJ2qm982+38Zf/KjibVOF1dEbVdrGZmII6Tg5DaQzNXGYkg5PvYmJgT9xRsqeQjeYIUYqYZpAt+HYWA38AVfMU8jip/1P1wmwqD469nzJOBBa8yfsMs6Ca7tBaNl/zTxCRGnAgEzqtkdQ=
file_glob: true file_glob: true

8
ChangeLog.md

@ -4,7 +4,7 @@ Note: This file only contains high level features or important fixes.
## 4.0 ## 4.0
### 4.0.0 - Daily Build ### 4.0.0 - Stable
* Added ROI option during manual flight. * 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
@ -15,9 +15,7 @@ Note: This file only contains high level features or important fixes.
* Plan View: New create plan UI for initial plan creation * Plan View: New create plan UI for initial plan creation
* New Corridor editing tools ui. Includes ability to trace polyline by clicking. * New Corridor editing tools ui. Includes ability to trace polyline by clicking.
* New Polygon editing tools ui. Includes ability to trace polygon by clicking. * New Polygon editing tools ui. Includes ability to trace polygon by clicking.
* ArduCopter/Rover: Follow Me setup page
* More performant flight path display algorithm. Mobile builds no longer show limited path length. * More performant flight path display algorithm. Mobile builds no longer show limited path length.
* ArduCopter/Rover: Add support for Follow Me
* ArduPilot: Add Motor Test vehicle setup page * ArduPilot: Add Motor Test vehicle setup page
* Compass Instrument: Add indicators for Home, COG and Next Waypoint headings. * Compass Instrument: Add indicators for Home, COG and Next Waypoint headings.
* Log Replay: Support changing speed of playback * Log Replay: Support changing speed of playback
@ -52,9 +50,9 @@ Note: This file only contains high level features or important fixes.
* ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page. * ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page.
* Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans. * Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans.
### 3.5.6 - Not yet released ## 3.5
### 3.5.5 - Stable ### 3.5.5
* Fix mavlink message memset which cause wrong commands to be sent on ArduPilot GotoLocation. * Fix mavlink message memset which cause wrong commands to be sent on ArduPilot GotoLocation.
* Disable Pause when fixed wing is on landing approach. * Disable Pause when fixed wing is on landing approach.

2
QGCInstaller.pri

@ -27,7 +27,7 @@ installer {
# We cd to release directory so we can run macdeployqt without a path to the # We cd to release directory so we can run macdeployqt without a path to the
# qgroundcontrol.app file. If you specify a path to the .app file the symbolic # qgroundcontrol.app file. If you specify a path to the .app file the symbolic
# links to plugins will not be created correctly. # links to plugins will not be created correctly.
QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=2 -qmldir=$${BASEDIR}/src QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=1 -qmldir=$${BASEDIR}/src
# macdeployqt is missing some relocations once in a while. "Fix" it: # macdeployqt is missing some relocations once in a while. "Fix" it:
QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1 QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1

7
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc

@ -53,7 +53,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent)
, _tuningComponent (nullptr) , _tuningComponent (nullptr)
, _esp8266Component (nullptr) , _esp8266Component (nullptr)
, _heliComponent (nullptr) , _heliComponent (nullptr)
#if 0
// Follow me not ready for Stable
, _followComponent (nullptr) , _followComponent (nullptr)
#endif
{ {
#if !defined(NO_SERIAL_LINK) && !defined(__android__) #if !defined(NO_SERIAL_LINK) && !defined(__android__)
connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack); connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack);
@ -104,12 +107,16 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_safetyComponent->setupTriggerSignals(); _safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
#if 0
// Follow me not ready for Stable
if ((qobject_cast<ArduCopterFirmwarePlugin*>(_vehicle->firmwarePlugin()) || qobject_cast<ArduRoverFirmwarePlugin*>(_vehicle->firmwarePlugin())) && if ((qobject_cast<ArduCopterFirmwarePlugin*>(_vehicle->firmwarePlugin()) || qobject_cast<ArduRoverFirmwarePlugin*>(_vehicle->firmwarePlugin())) &&
_vehicle->parameterManager()->parameterExists(-1, QStringLiteral("FOLL_ENABLE"))) { _vehicle->parameterManager()->parameterExists(-1, QStringLiteral("FOLL_ENABLE"))) {
_followComponent = new APMFollowComponent(_vehicle, this); _followComponent = new APMFollowComponent(_vehicle, this);
_followComponent->setupTriggerSignals(); _followComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_followComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_followComponent));
} }
#endif
if (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER && (_vehicle->versionCompare(4, 0, 0) >= 0)) { if (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER && (_vehicle->versionCompare(4, 0, 0) >= 0)) {
_heliComponent = new APMHeliComponent(_vehicle, this); _heliComponent = new APMHeliComponent(_vehicle, this);

3
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h

@ -57,7 +57,10 @@ protected:
APMTuningComponent* _tuningComponent; APMTuningComponent* _tuningComponent;
ESP8266Component* _esp8266Component; ESP8266Component* _esp8266Component;
APMHeliComponent* _heliComponent; APMHeliComponent* _heliComponent;
#if 0
// Follow me not ready for Stable
APMFollowComponent* _followComponent; APMFollowComponent* _followComponent;
#endif
#if !defined(NO_SERIAL_LINK) && !defined(__android__) #if !defined(NO_SERIAL_LINK) && !defined(__android__)
private slots: private slots:

9
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -43,7 +43,10 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
{ GUIDED_NOGPS, "Guided No GPS"}, { GUIDED_NOGPS, "Guided No GPS"},
{ SMART_RTL, "Smart RTL"}, { SMART_RTL, "Smart RTL"},
{ FLOWHOLD, "Flow Hold" }, { FLOWHOLD, "Flow Hold" },
#if 0
// Follow me not ready for Stable
{ FOLLOW, "Follow" }, { FOLLOW, "Follow" },
#endif
{ ZIGZAG, "ZigZag" }, { ZIGZAG, "ZigZag" },
}); });
} }
@ -71,7 +74,10 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
APMCopterMode(APMCopterMode::GUIDED_NOGPS, true), APMCopterMode(APMCopterMode::GUIDED_NOGPS, true),
APMCopterMode(APMCopterMode::SMART_RTL, true), APMCopterMode(APMCopterMode::SMART_RTL, true),
APMCopterMode(APMCopterMode::FLOWHOLD, true), APMCopterMode(APMCopterMode::FLOWHOLD, true),
#if 0
// Follow me not ready for Stable
APMCopterMode(APMCopterMode::FOLLOW, true), APMCopterMode(APMCopterMode::FOLLOW, true),
#endif
APMCopterMode(APMCopterMode::ZIGZAG, true), APMCopterMode(APMCopterMode::ZIGZAG, true),
}); });
@ -141,7 +147,10 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
return true; return true;
} }
#if 0
// Follow me not ready for Stable
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{ {
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
} }
#endif

6
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h

@ -43,7 +43,10 @@ public:
GUIDED_NOGPS= 20, GUIDED_NOGPS= 20,
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder
#if 0
// Follow me not ready for Stable
FOLLOW = 23, // follow attempts to follow another vehicle or ground station FOLLOW = 23, // follow attempts to follow another vehicle or ground station
#endif
ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
}; };
@ -71,7 +74,10 @@ public:
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override; bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; } bool supportsSmartRTL (void) const override { return true; }
#if 0
// Follow me not ready for Stable
void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
#endif
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;

9
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc

@ -22,7 +22,10 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
{STEERING, "Steering"}, {STEERING, "Steering"},
{HOLD, "Hold"}, {HOLD, "Hold"},
{LOITER, "Loiter"}, {LOITER, "Loiter"},
#if 0
// Follow me not ready for Stable
{FOLLOW, "Follow"}, {FOLLOW, "Follow"},
#endif
{SIMPLE, "Simple"}, {SIMPLE, "Simple"},
{AUTO, "Auto"}, {AUTO, "Auto"},
{RTL, "RTL"}, {RTL, "RTL"},
@ -40,7 +43,10 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
APMRoverMode(APMRoverMode::STEERING ,true), APMRoverMode(APMRoverMode::STEERING ,true),
APMRoverMode(APMRoverMode::HOLD ,true), APMRoverMode(APMRoverMode::HOLD ,true),
APMRoverMode(APMRoverMode::LOITER ,true), APMRoverMode(APMRoverMode::LOITER ,true),
#if 0
// Follow me not ready for Stable
APMRoverMode(APMRoverMode::FOLLOW ,true), APMRoverMode(APMRoverMode::FOLLOW ,true),
#endif
APMRoverMode(APMRoverMode::SIMPLE ,true), APMRoverMode(APMRoverMode::SIMPLE ,true),
APMRoverMode(APMRoverMode::AUTO ,true), APMRoverMode(APMRoverMode::AUTO ,true),
APMRoverMode(APMRoverMode::RTL ,true), APMRoverMode(APMRoverMode::RTL ,true),
@ -78,7 +84,10 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
return true; return true;
} }
#if 0
// Follow me not ready for Stable
void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{ {
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
} }
#endif

6
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

@ -25,7 +25,10 @@ public:
STEERING = 3, STEERING = 3,
HOLD = 4, HOLD = 4,
LOITER = 5, LOITER = 5,
#if 0
// Follow me not ready for Stable
FOLLOW = 6, FOLLOW = 6,
#endif
SIMPLE = 7, SIMPLE = 7,
AUTO = 10, AUTO = 10,
RTL = 11, RTL = 11,
@ -53,7 +56,10 @@ public:
bool supportsNegativeThrust (Vehicle *) final; bool supportsNegativeThrust (Vehicle *) final;
bool supportsSmartRTL (void) const override { return true; } bool supportsSmartRTL (void) const override { return true; }
QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); } QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); }
#if 0
// Follow me not ready for Stable
void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
#endif
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;

34
src/FlightDisplay/PreFlightCheckList.qml

@ -66,23 +66,25 @@ Rectangle {
//-- Pick a checklist model that matches the current airframe type (if any) //-- Pick a checklist model that matches the current airframe type (if any)
function _updateModel() { function _updateModel() {
if(activeVehicle) { var vehicle = activeVehicle
if(activeVehicle.multiRotor) { if (!vehicle) {
modelContainer.source = "/checklists/MultiRotorChecklist.qml" vehicle = QGroundControl.multiVehicleManager.offlineEditingVehicle
} else if(activeVehicle.vtol) { }
modelContainer.source = "/checklists/VTOLChecklist.qml"
} else if(activeVehicle.rover) { if(vehicle.multiRotor) {
modelContainer.source = "/checklists/RoverChecklist.qml" modelContainer.source = "/checklists/MultiRotorChecklist.qml"
} else if(activeVehicle.sub) { } else if(vehicle.vtol) {
modelContainer.source = "/checklists/SubChecklist.qml" modelContainer.source = "/checklists/VTOLChecklist.qml"
} else if(activeVehicle.fixedWing) { } else if(vehicle.rover) {
modelContainer.source = "/checklists/FixedWingChecklist.qml" modelContainer.source = "/checklists/RoverChecklist.qml"
} else { } else if(vehicle.sub) {
modelContainer.source = "/checklists/DefaultChecklist.qml" modelContainer.source = "/checklists/SubChecklist.qml"
} } else if(vehicle.fixedWing) {
return modelContainer.source = "/checklists/FixedWingChecklist.qml"
} else {
modelContainer.source = "/checklists/DefaultChecklist.qml"
} }
modelContainer.source = "/checklists/DefaultChecklist.qml" return
} }
Component.onCompleted: { Component.onCompleted: {

23
src/FlightMap/Widgets/MapFitFunctions.qml

@ -62,8 +62,14 @@ Item {
var east = normalizeLon(coordList[0].longitude) var east = normalizeLon(coordList[0].longitude)
var west = east var west = east
for (var i = 1; i < coordList.length; i++) { for (var i = 1; i < coordList.length; i++) {
var lat = normalizeLat(coordList[i].latitude) var lat = coordList[i].latitude
var lon = normalizeLon(coordList[i].longitude) var lon = coordList[i].longitude
if (isNaN(lat) || lat == 0 || isNan(lon) || lon == 0) {
// Be careful of invalid coords which can happen when items are not yet complete
continue
}
lat = normalizeLat(lat)
lon = normalizeLon(lat)
north = Math.max(north, lat) north = Math.max(north, lat)
south = Math.min(south, lat) south = Math.min(south, lat)
east = Math.max(east, lon) east = Math.max(east, lon)
@ -110,19 +116,6 @@ Item {
// Being called prior to controller.start // Being called prior to controller.start
return return
} }
/*
for (var i=1; i<_missionController.visualItems.count; i++) {
var missionItem = _missionController.visualItems.get(i)
if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) {
console.log(missionItem.boundingCube.pointNW)
console.log(missionItem.boundingCube.pointSE)
var loc = QtPositioning.rectangle(missionItem.boundingCube.pointNW, missionItem.boundingCube.pointSE)
console.log(loc)
map.visibleRegion = loc
return
}
}
*/
var coordList = [ ] var coordList = [ ]
addMissionItemCoordsForFit(coordList) addMissionItemCoordsForFit(coordList)
fitMapViewportToAllCoordinates(coordList) fitMapViewportToAllCoordinates(coordList)

1
src/QmlControls/ToolStrip.qml

@ -29,6 +29,7 @@ Rectangle {
property AbstractButton lastClickedButton: null property AbstractButton lastClickedButton: null
function simulateClick(buttonIndex) { function simulateClick(buttonIndex) {
buttonIndex = buttonIndex + 1 // skip over title
toolStripColumn.children[buttonIndex].checked = true toolStripColumn.children[buttonIndex].checked = true
toolStripColumn.children[buttonIndex].clicked() toolStripColumn.children[buttonIndex].clicked()
} }

7
src/Vehicle/Vehicle.cc

@ -3323,6 +3323,8 @@ void Vehicle::_sendMavCommandAgain()
_mavCommandAckTimer.start(); _mavCommandAckTimer.start();
qCDebug(VehicleLog) << "_sendMavCommandAgain sending" << queuedCommand.command;
mavlink_message_t msg; mavlink_message_t msg;
if (queuedCommand.commandInt) { if (queuedCommand.commandInt) {
mavlink_command_int_t cmd; mavlink_command_int_t cmd;
@ -3428,6 +3430,8 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
mavlink_command_ack_t ack; mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&message, &ack); mavlink_msg_command_ack_decode(&message, &ack);
qCDebug(VehicleLog) << QStringLiteral("_handleCommandAck command(%1) result(%2)").arg(ack.command).arg(ack.result);
if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) {
qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result); qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result);
_handleUnsupportedRequestAutopilotCapabilities(); _handleUnsupportedRequestAutopilotCapabilities();
@ -3878,7 +3882,8 @@ void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
vehicleInfo.availableFlags = 0; vehicleInfo.availableFlags = 0;
vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7); vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7);
vehicleInfo.location.setLatitude(adsbVehicleMsg.lon / 1e7); vehicleInfo.location.setLongitude(adsbVehicleMsg.lon / 1e7);
vehicleInfo.availableFlags |= ADSBVehicle::LocationAvailable;
vehicleInfo.callsign = adsbVehicleMsg.callsign; vehicleInfo.callsign = adsbVehicleMsg.callsign;
vehicleInfo.availableFlags |= ADSBVehicle::CallsignAvailable; vehicleInfo.availableFlags |= ADSBVehicle::CallsignAvailable;

27
src/VehicleSetup/FirmwareUpgradeController.cc

@ -724,28 +724,39 @@ void FirmwareUpgradeController::setSelectedFirmwareBuildType(FirmwareBuildType_t
void FirmwareUpgradeController::_buildAPMFirmwareNames(void) void FirmwareUpgradeController::_buildAPMFirmwareNames(void)
{ {
#if !defined(NO_ARDUPILOT_DIALECT) #if !defined(NO_ARDUPILOT_DIALECT)
qCDebug(FirmwareUpgradeLog) << "_buildAPMFirmwareNames";
bool chibios = _apmChibiOSSetting->rawValue().toInt() == 0; bool chibios = _apmChibiOSSetting->rawValue().toInt() == 0;
FirmwareVehicleType_t vehicleType = static_cast<FirmwareVehicleType_t>(_apmVehicleTypeSetting->rawValue().toInt()); FirmwareVehicleType_t vehicleType = static_cast<FirmwareVehicleType_t>(_apmVehicleTypeSetting->rawValue().toInt());
QString boardDescription = _foundBoardInfo.description();
quint16 boardVID = _foundBoardInfo.vendorIdentifier();
quint16 boardPID = _foundBoardInfo.productIdentifier();
#if 0
// This is left in for debugging manifest problems
boardDescription = "KakuteF7";
boardVID = 1155;
boardPID = 22336;
#endif
qCDebug(FirmwareUpgradeLog) << QStringLiteral("_buildAPMFirmwareNames description(%1) vid(%2/0x%3) pid(%4/0x%5)").arg(boardDescription).arg(boardVID).arg(boardVID, 1, 16).arg(boardPID).arg(boardPID, 1, 16);
_apmFirmwareNames.clear(); _apmFirmwareNames.clear();
_apmFirmwareUrls.clear(); _apmFirmwareUrls.clear();
QString apmDescriptionSuffix("-BL"); QString apmDescriptionSuffix("-BL");
bool bootloaderMatch = _foundBoardInfo.description().endsWith(apmDescriptionSuffix); bool bootloaderMatch = boardDescription.endsWith(apmDescriptionSuffix);
for (const ManifestFirmwareInfo_t& firmwareInfo: _rgManifestFirmwareInfo) { for (const ManifestFirmwareInfo_t& firmwareInfo: _rgManifestFirmwareInfo) {
bool match = false; bool match = false;
if (firmwareInfo.firmwareBuildType == _selectedFirmwareBuildType && firmwareInfo.chibios == chibios && firmwareInfo.vehicleType == vehicleType) { if (firmwareInfo.firmwareBuildType == _selectedFirmwareBuildType && firmwareInfo.chibios == chibios && firmwareInfo.vehicleType == vehicleType) {
if (bootloaderMatch) { if (bootloaderMatch) {
if (firmwareInfo.rgBootloaderPortString.contains(_foundBoardInfo.description())) { if (firmwareInfo.rgBootloaderPortString.contains(boardDescription)) {
qCDebug(FirmwareUpgradeLog) << "Bootloader match:" << firmwareInfo.friendlyName << _foundBoardInfo.description() << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; qCDebug(FirmwareUpgradeLog) << "Bootloader match:" << firmwareInfo.friendlyName << boardDescription << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType;
match = true; match = true;
} }
} else { } else {
if (firmwareInfo.rgVID.contains(_foundBoardInfo.vendorIdentifier()) && firmwareInfo.rgPID.contains(_foundBoardInfo.productIdentifier())) { if (firmwareInfo.rgVID.contains(boardVID) && firmwareInfo.rgPID.contains(boardPID)) {
qCDebug(FirmwareUpgradeLog) << "Fallback match:" << firmwareInfo.friendlyName << _foundBoardInfo.vendorIdentifier() << _foundBoardInfo.productIdentifier() << _bootloaderBoardID << firmwareInfo.url << firmwareInfo.vehicleType; qCDebug(FirmwareUpgradeLog) << "VID/PID match:" << firmwareInfo.friendlyName << boardVID << boardPID << _bootloaderBoardID << firmwareInfo.url << firmwareInfo.vehicleType;
match = true; match = true;
} }
} }

Loading…
Cancel
Save