Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
be4e5dc3
Commit
be4e5dc3
authored
Nov 14, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Use new QGCSerialPortInfo
parent
946b7ea8
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
51 additions
and
119 deletions
+51
-119
FirmwareUpgradeController.cc
src/VehicleSetup/FirmwareUpgradeController.cc
+5
-5
PX4FirmwareUpgradeThread.cc
src/VehicleSetup/PX4FirmwareUpgradeThread.cc
+9
-60
PX4FirmwareUpgradeThread.h
src/VehicleSetup/PX4FirmwareUpgradeThread.h
+8
-16
LinkManager.cc
src/comm/LinkManager.cc
+29
-38
No files found.
src/VehicleSetup/FirmwareUpgradeController.cc
View file @
be4e5dc3
...
...
@@ -109,23 +109,23 @@ void FirmwareUpgradeController::_foundBoard(bool firstAttempt, const QSerialPort
{
_foundBoardInfo
=
info
;
switch
(
type
)
{
case
FoundBoard
PX4FMUV1
:
case
QGCSerialPortInfo
:
:
BoardType
PX4FMUV1
:
_foundBoardType
=
"PX4 FMU V1"
;
_startFlashWhenBootloaderFound
=
false
;
break
;
case
FoundBoard
PX4FMUV2
:
case
QGCSerialPortInfo
:
:
BoardType
PX4FMUV2
:
_foundBoardType
=
"Pixhawk"
;
_startFlashWhenBootloaderFound
=
false
;
break
;
case
FoundBoard
AeroCore
:
case
QGCSerialPortInfo
:
:
BoardType
AeroCore
:
_foundBoardType
=
"AeroCore"
;
_startFlashWhenBootloaderFound
=
false
;
break
;
case
FoundBoard
PX4Flow
:
case
QGCSerialPortInfo
:
:
BoardType
PX4Flow
:
_foundBoardType
=
"PX4 Flow"
;
_startFlashWhenBootloaderFound
=
false
;
break
;
case
FoundBoard
3drRadio
:
case
QGCSerialPortInfo
:
:
BoardType
3drRadio
:
_foundBoardType
=
"3DR Radio"
;
if
(
!
firstAttempt
)
{
// Radio always flashes latest firmware, so we can start right away without
...
...
src/VehicleSetup/PX4FirmwareUpgradeThread.cc
View file @
be4e5dc3
...
...
@@ -29,10 +29,8 @@
#include "Bootloader.h"
#include "QGCLoggingCategory.h"
#include "QGC.h"
#include "SerialPortIds.h"
#include <QTimer>
#include <QSerialPortInfo>
#include <QDebug>
#include <QSerialPort>
...
...
@@ -99,8 +97,8 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"_findBoardOnce"
;
Q
SerialPortInfo
portInfo
;
PX4FirmwareUpgradeFound
BoardType_t
boardType
;
Q
GCSerialPortInfo
portInfo
;
QGCSerialPortInfo
::
BoardType_t
boardType
;
if
(
_findBoardFromPorts
(
portInfo
,
boardType
))
{
if
(
!
_foundBoard
)
{
...
...
@@ -108,7 +106,7 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
_foundBoardPortInfo
=
portInfo
;
emit
foundBoard
(
_findBoardFirstAttempt
,
portInfo
,
boardType
);
if
(
!
_findBoardFirstAttempt
)
{
if
(
boardType
==
FoundBoard
3drRadio
)
{
if
(
boardType
==
QGCSerialPortInfo
::
BoardType
3drRadio
)
{
_3drRadioForceBootloader
(
portInfo
);
return
;
}
else
{
...
...
@@ -131,11 +129,9 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
_timerRetry
->
start
();
}
bool
PX4FirmwareUpgradeThreadWorker
::
_findBoardFromPorts
(
Q
SerialPortInfo
&
portInfo
,
PX4FirmwareUpgradeFoundBoardType_t
&
t
ype
)
bool
PX4FirmwareUpgradeThreadWorker
::
_findBoardFromPorts
(
Q
GCSerialPortInfo
&
portInfo
,
QGCSerialPortInfo
::
BoardType_t
&
boardT
ype
)
{
bool
found
=
false
;
foreach
(
QSerialPortInfo
info
,
QSerialPortInfo
::
availablePorts
())
{
foreach
(
QGCSerialPortInfo
info
,
QGCSerialPortInfo
::
availablePorts
())
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Serial Port --------------"
;
qCDebug
(
FirmwareUpgradeLog
)
<<
"
\t
port name:"
<<
info
.
portName
();
qCDebug
(
FirmwareUpgradeLog
)
<<
"
\t
description:"
<<
info
.
description
();
...
...
@@ -143,55 +139,8 @@ bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QSerialPortInfo& portIn
qCDebug
(
FirmwareUpgradeLog
)
<<
"
\t
vendor ID:"
<<
info
.
vendorIdentifier
();
qCDebug
(
FirmwareUpgradeLog
)
<<
"
\t
product ID:"
<<
info
.
productIdentifier
();
if
(
!
info
.
portName
().
isEmpty
())
{
switch
(
info
.
vendorIdentifier
())
{
case
SerialPortIds
:
:
px4VendorId
:
if
(
info
.
productIdentifier
()
==
SerialPortIds
::
pixhawkFMUV2ProductId
||
info
.
productIdentifier
()
==
SerialPortIds
::
pixhawkFMUV2OldBootloaderProductId
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found PX4 FMU V2"
;
type
=
FoundBoardPX4FMUV2
;
found
=
true
;
}
else
if
(
info
.
productIdentifier
()
==
SerialPortIds
::
pixhawkFMUV1ProductId
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found PX4 FMU V1"
;
type
=
FoundBoardPX4FMUV1
;
found
=
true
;
}
else
if
(
info
.
productIdentifier
()
==
SerialPortIds
::
px4FlowProductId
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found PX4 Flow"
;
type
=
FoundBoardPX4Flow
;
found
=
true
;
}
else
if
(
info
.
productIdentifier
()
==
SerialPortIds
::
AeroCoreProductId
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found AeroCore"
;
type
=
FoundBoardAeroCore
;
found
=
true
;
}
break
;
case
SerialPortIds
:
:
threeDRRadioVendorId
:
if
(
info
.
productIdentifier
()
==
SerialPortIds
::
threeDRRadioProductId
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found 3DR Radio"
;
type
=
FoundBoard3drRadio
;
found
=
true
;
}
break
;
}
if
(
!
found
)
{
// Fall back to port name matching which could lead to incorrect board mapping. But in some cases the
// vendor and product id do not come through correctly so this is used as a last chance detection method.
if
(
info
.
description
()
==
"PX4 FMU v2.x"
||
info
.
description
()
==
"PX4 BL FMU v2.x"
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found PX4 FMU V2 (by name matching fallback)"
;
type
=
FoundBoardPX4FMUV2
;
found
=
true
;
}
else
if
(
info
.
description
()
==
"PX4 FMU v1.x"
||
info
.
description
()
==
"PX4 BL FMU v1.x"
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found PX4 FMU V1 (by name matching fallback)"
;
type
=
FoundBoardPX4FMUV1
;
found
=
true
;
}
else
if
(
info
.
description
().
startsWith
(
"PX4 FMU"
))
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"Found PX4 FMU, assuming V2 (by name matching fallback)"
;
type
=
FoundBoardPX4FMUV2
;
found
=
true
;
}
}
}
if
(
found
)
{
boardType
=
info
.
boardType
();
if
(
boardType
!=
QGCSerialPortInfo
::
BoardTypeUnknown
)
{
portInfo
=
info
;
return
true
;
}
...
...
@@ -200,7 +149,7 @@ bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QSerialPortInfo& portIn
return
false
;
}
void
PX4FirmwareUpgradeThreadWorker
::
_3drRadioForceBootloader
(
const
QSerialPortInfo
&
portInfo
)
void
PX4FirmwareUpgradeThreadWorker
::
_3drRadioForceBootloader
(
const
Q
GC
SerialPortInfo
&
portInfo
)
{
// First make sure we can't get the bootloader
...
...
@@ -257,7 +206,7 @@ void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QSerialPortI
_findBootloader
(
portInfo
,
true
/* radio mode */
,
true
/* errorOnNotFound */
);
}
bool
PX4FirmwareUpgradeThreadWorker
::
_findBootloader
(
const
QSerialPortInfo
&
portInfo
,
bool
radioMode
,
bool
errorOnNotFound
)
bool
PX4FirmwareUpgradeThreadWorker
::
_findBootloader
(
const
Q
GC
SerialPortInfo
&
portInfo
,
bool
radioMode
,
bool
errorOnNotFound
)
{
qCDebug
(
FirmwareUpgradeLog
)
<<
"_findBootloader"
;
...
...
src/VehicleSetup/PX4FirmwareUpgradeThread.h
View file @
be4e5dc3
...
...
@@ -30,25 +30,17 @@
#include "Bootloader.h"
#include "FirmwareImage.h"
#include "QGCSerialPortInfo.h"
#include <QObject>
#include <QThread>
#include <QTimer>
#include <QTime>
#include <QSerialPortInfo>
#include "qextserialport.h"
#include <stdint.h>
typedef
enum
{
FoundBoardPX4FMUV1
,
FoundBoardPX4FMUV2
,
FoundBoardPX4Flow
,
FoundBoard3drRadio
,
FoundBoardAeroCore
}
PX4FirmwareUpgradeFoundBoardType_t
;
class
PX4FirmwareUpgradeThreadController
;
/// @brief Used to run bootloader commands on a seperate thread. These routines are mainly meant to to be called
...
...
@@ -64,7 +56,7 @@ public:
signals:
void
updateProgress
(
int
curr
,
int
total
);
void
foundBoard
(
bool
firstAttempt
,
const
QSerialPortInfo
&
portInfo
,
int
type
);
void
foundBoard
(
bool
firstAttempt
,
const
Q
GC
SerialPortInfo
&
portInfo
,
int
type
);
void
noBoardFound
(
void
);
void
boardGone
(
void
);
void
foundBootloader
(
int
bootloaderVersion
,
int
boardID
,
int
flashSize
);
...
...
@@ -85,9 +77,9 @@ private slots:
void
_cancel
(
void
);
private:
bool
_findBoardFromPorts
(
Q
SerialPortInfo
&
portInfo
,
PX4FirmwareUpgradeFoundBoardType_t
&
t
ype
);
bool
_findBootloader
(
const
QSerialPortInfo
&
portInfo
,
bool
radioMode
,
bool
errorOnNotFound
);
void
_3drRadioForceBootloader
(
const
QSerialPortInfo
&
portInfo
);
bool
_findBoardFromPorts
(
Q
GCSerialPortInfo
&
portInfo
,
QGCSerialPortInfo
::
BoardType_t
&
boardT
ype
);
bool
_findBootloader
(
const
Q
GC
SerialPortInfo
&
portInfo
,
bool
radioMode
,
bool
errorOnNotFound
);
void
_3drRadioForceBootloader
(
const
Q
GC
SerialPortInfo
&
portInfo
);
bool
_erase
(
void
);
PX4FirmwareUpgradeThreadController
*
_controller
;
...
...
@@ -100,7 +92,7 @@ private:
bool
_foundBoard
;
///< true: board is currently connected
bool
_findBoardFirstAttempt
;
///< true: this is our first try looking for a board
Q
SerialPortInfo
_foundBoardPortInfo
;
///< port info for found board
Q
GCSerialPortInfo
_foundBoardPortInfo
;
///< port info for found board
};
/// @brief Provides methods to interact with the bootloader. The commands themselves are signalled
...
...
@@ -128,7 +120,7 @@ public:
signals:
/// @brief Emitted by the find board process when it finds a board.
void
foundBoard
(
bool
firstAttempt
,
const
Q
SerialPortInfo
&
portInfo
,
int
t
ype
);
void
foundBoard
(
bool
firstAttempt
,
const
Q
GCSerialPortInfo
&
portInfo
,
int
boardT
ype
);
void
noBoardFound
(
void
);
...
...
@@ -163,7 +155,7 @@ signals:
void
_cancel
(
void
);
private
slots
:
void
_foundBoard
(
bool
firstAttempt
,
const
QSerialPortInfo
&
portInfo
,
int
type
)
{
emit
foundBoard
(
firstAttempt
,
portInfo
,
type
);
}
void
_foundBoard
(
bool
firstAttempt
,
const
Q
GC
SerialPortInfo
&
portInfo
,
int
type
)
{
emit
foundBoard
(
firstAttempt
,
portInfo
,
type
);
}
void
_noBoardFound
(
void
)
{
emit
noBoardFound
();
}
void
_boardGone
(
void
)
{
emit
boardGone
();
}
void
_foundBootloader
(
int
bootloaderVersion
,
int
boardID
,
int
flashSize
)
{
emit
foundBootloader
(
bootloaderVersion
,
boardID
,
flashSize
);
}
...
...
src/comm/LinkManager.cc
View file @
be4e5dc3
...
...
@@ -34,18 +34,13 @@ This file is part of the QGROUNDCONTROL project
#include <QDebug>
#ifndef __ios__
#ifdef __android__
#include "qserialportinfo.h"
#else
#include <QSerialPortInfo>
#endif
#include "QGCSerialPortInfo.h"
#endif
#include "LinkManager.h"
#include "MainWindow.h"
#include "QGCMessageBox.h"
#include "QGCApplication.h"
#include "SerialPortIds.h"
#include "QGCApplication.h"
QGC_LOGGING_CATEGORY
(
LinkManagerLog
,
"LinkManagerLog"
)
...
...
@@ -489,9 +484,9 @@ void LinkManager::_updateConfigurationList(void)
}
bool
saveList
=
false
;
QStringList
currentPorts
;
QList
<
Q
SerialPortInfo
>
portList
=
Q
SerialPortInfo
::
availablePorts
();
QList
<
Q
GCSerialPortInfo
>
portList
=
QGC
SerialPortInfo
::
availablePorts
();
// Iterate Comm Ports
foreach
(
QSerialPortInfo
portInfo
,
portList
)
{
foreach
(
Q
GC
SerialPortInfo
portInfo
,
portList
)
{
#if 0
// Too noisy for most logging, so turn on as needed
qCDebug(LinkManagerLog) << "-----------------------------------------------------";
...
...
@@ -504,8 +499,15 @@ void LinkManager::_updateConfigurationList(void)
#endif
// Save port name
currentPorts
<<
portInfo
.
systemLocation
();
// Is this a PX4 and NOT in bootloader mode?
if
(
portInfo
.
vendorIdentifier
()
==
SerialPortIds
::
px4VendorId
&&
!
portInfo
.
description
().
contains
(
"BL"
))
{
QGCSerialPortInfo
::
BoardType_t
boardType
=
portInfo
.
boardType
();
if
(
boardType
!=
QGCSerialPortInfo
::
BoardTypeUnknown
)
{
if
(
portInfo
.
isBootloader
())
{
// Don't connect to bootloader
continue
;
}
SerialConfiguration
*
pSerial
=
_findSerialConfiguration
(
portInfo
.
systemLocation
());
if
(
pSerial
)
{
//-- If this port is configured make sure it has the preferred flag set
...
...
@@ -514,45 +516,34 @@ void LinkManager::_updateConfigurationList(void)
saveList
=
true
;
}
}
else
{
// Lets create a new Serial configuration automatically
if
(
portInfo
.
description
()
==
"AeroCore"
)
{
switch
(
boardType
)
{
case
QGCSerialPortInfo
:
:
BoardTypePX4FMUV1
:
case
QGCSerialPortInfo
:
:
BoardTypePX4FMUV2
:
pSerial
=
new
SerialConfiguration
(
QString
(
"Pixhawk on %1"
).
arg
(
portInfo
.
portName
().
trimmed
()));
break
;
case
QGCSerialPortInfo
:
:
BoardTypeAeroCore
:
pSerial
=
new
SerialConfiguration
(
QString
(
"AeroCore on %1"
).
arg
(
portInfo
.
portName
().
trimmed
()));
}
else
if
(
portInfo
.
description
().
contains
(
"PX4Flow"
))
{
break
;
case
QGCSerialPortInfo
:
:
BoardTypePX4Flow
:
pSerial
=
new
SerialConfiguration
(
QString
(
"PX4Flow on %1"
).
arg
(
portInfo
.
portName
().
trimmed
()));
}
else
if
(
portInfo
.
description
().
contains
(
"PX4"
))
{
pSerial
=
new
SerialConfiguration
(
QString
(
"Pixhawk on %1"
).
arg
(
portInfo
.
portName
().
trimmed
()));
}
else
{
continue
;
}
pSerial
->
setDynamic
(
true
);
pSerial
->
setPreferred
(
true
);
pSerial
->
setBaud
(
115200
);
pSerial
->
setPortName
(
portInfo
.
systemLocation
());
addLinkConfiguration
(
pSerial
);
saveList
=
true
;
}
}
// Is this an FTDI Chip? It could be a 3DR Modem
if
(
portInfo
.
vendorIdentifier
()
==
SerialPortIds
::
threeDRRadioVendorId
&&
portInfo
.
productIdentifier
()
==
SerialPortIds
::
threeDRRadioProductId
)
{
SerialConfiguration
*
pSerial
=
_findSerialConfiguration
(
portInfo
.
systemLocation
());
if
(
pSerial
)
{
//-- If this port is configured make sure it has the preferred flag set, unless someone else already has it set.
if
(
!
pSerial
->
isPreferred
()
&&
!
saveList
)
{
pSerial
->
setPreferred
(
true
);
saveList
=
true
;
break
;
case
QGCSerialPortInfo
:
:
BoardType3drRadio
:
pSerial
=
new
SerialConfiguration
(
QString
(
"3DR Radio on %1"
).
arg
(
portInfo
.
portName
().
trimmed
()));
default:
qWarning
()
<<
"Internal error"
;
break
;
}
}
else
{
// Lets create a new Serial configuration automatically (an assumption at best)
pSerial
=
new
SerialConfiguration
(
QString
(
"3DR Radio on %1"
).
arg
(
portInfo
.
portName
().
trimmed
()));
pSerial
->
setBaud
(
boardType
==
QGCSerialPortInfo
::
BoardType3drRadio
?
57600
:
115200
);
pSerial
->
setDynamic
(
true
);
pSerial
->
setPreferred
(
true
);
pSerial
->
setBaud
(
57600
);
pSerial
->
setPortName
(
portInfo
.
systemLocation
());
addLinkConfiguration
(
pSerial
);
saveList
=
true
;
}
}
}
// Now we go through the current configuration list and make sure any dynamic config has gone away
QList
<
LinkConfiguration
*>
_confToDelete
;
foreach
(
LinkConfiguration
*
pLink
,
_linkConfigurations
)
{
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment