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
50089289
Commit
50089289
authored
Jun 22, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Rover fixes
parent
53a49fdc
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
51 additions
and
21 deletions
+51
-21
APMFlightModesComponent.qml
src/AutoPilotPlugins/APM/APMFlightModesComponent.qml
+6
-3
APMFlightModesComponentController.cc
...AutoPilotPlugins/APM/APMFlightModesComponentController.cc
+8
-4
APMFlightModesComponentController.h
src/AutoPilotPlugins/APM/APMFlightModesComponentController.h
+4
-0
APMFlightModesComponentSummary.qml
src/AutoPilotPlugins/APM/APMFlightModesComponentSummary.qml
+8
-6
APMSensorsComponent.cc
src/AutoPilotPlugins/APM/APMSensorsComponent.cc
+17
-7
APMParameterMetaData.cc
src/FirmwarePlugin/APM/APMParameterMetaData.cc
+1
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+5
-0
Vehicle.h
src/Vehicle/Vehicle.h
+2
-0
No files found.
src/AutoPilotPlugins/APM/APMFlightModesComponent.qml
View file @
50089289
...
...
@@ -22,13 +22,16 @@ QGCView {
id
:
rootQGCView
viewPanel
:
panel
readonly
property
string
_modeChannelParam
:
controller
.
modeChannelParam
readonly
property
string
_modeParamPrefix
:
controller
.
modeParamPrefix
property
real
_margins
:
ScreenTools
.
defaultFontPixelHeight
property
bool
_channel7OptionsAvailable
:
controller
.
parameterExists
(
-
1
,
"
CH7_OPT
"
)
// Not available in all firmware types
property
bool
_channel9OptionsAvailable
:
controller
.
parameterExists
(
-
1
,
"
CH9_OPT
"
)
// Not available in all firmware types
property
int
_channelOptionCount
:
_channel7OptionsAvailable
?
(
_channel9OptionsAvailable
?
6
:
2
)
:
0
property
Fact
_nullFact
property
bool
_fltmodeChExists
:
controller
.
parameterExists
(
-
1
,
"
FLTMODE_CH
"
)
property
Fact
_fltmodeCh
:
_fltmodeChExists
?
controller
.
getParameterFact
(
-
1
,
"
FLTMODE_CH
"
)
:
_nullFact
property
bool
_fltmodeChExists
:
controller
.
parameterExists
(
-
1
,
_modeChannelParam
)
property
Fact
_fltmodeCh
:
_fltmodeChExists
?
controller
.
getParameterFact
(
-
1
,
_modeChannelParam
)
:
_nullFact
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
panel
.
enabled
}
...
...
@@ -114,7 +117,7 @@ QGCView {
FactComboBox
{
id
:
modeCombo
width
:
ScreenTools
.
defaultFontPixelWidth
*
15
fact
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE
"
+
index
)
fact
:
controller
.
getParameterFact
(
-
1
,
_modeParamPrefix
+
index
)
indexModel
:
false
}
...
...
src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc
View file @
50089289
...
...
@@ -19,9 +19,13 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
:
_activeFlightMode
(
0
)
,
_channelCount
(
Vehicle
::
cMaxRcChannels
)
{
_modeParamPrefix
=
_vehicle
->
rover
()
?
"MODE"
:
"FLTMODE"
;
_modeChannelParam
=
_vehicle
->
rover
()
?
"MODE_CH"
:
"FLTMODE_CH"
;
QStringList
usedParams
;
usedParams
<<
QStringLiteral
(
"FLTMODE1"
)
<<
QStringLiteral
(
"FLTMODE2"
)
<<
QStringLiteral
(
"FLTMODE3"
)
<<
QStringLiteral
(
"FLTMODE4"
)
<<
QStringLiteral
(
"FLTMODE5"
)
<<
QStringLiteral
(
"FLTMODE6"
);
for
(
int
i
=
1
;
i
<
7
;
i
++
)
{
usedParams
<<
QStringLiteral
(
"%1%2"
).
arg
(
_modeParamPrefix
).
arg
(
i
);
}
if
(
!
_allParametersExists
(
FactSystem
::
defaultComponentId
,
usedParams
))
{
return
;
}
...
...
@@ -36,8 +40,8 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int
{
int
flightModeChannel
=
4
;
if
(
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"FLTMODE_CH"
)
))
{
flightModeChannel
=
getParameterFact
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"FLTMODE_CH"
)
)
->
rawValue
().
toInt
()
-
1
;
if
(
parameterExists
(
FactSystem
::
defaultComponentId
,
_modeChannelParam
))
{
flightModeChannel
=
getParameterFact
(
FactSystem
::
defaultComponentId
,
_modeChannelParam
)
->
rawValue
().
toInt
()
-
1
;
}
if
(
flightModeChannel
>=
channelCount
)
{
...
...
src/AutoPilotPlugins/APM/APMFlightModesComponentController.h
View file @
50089289
...
...
@@ -29,6 +29,8 @@ class APMFlightModesComponentController : public FactPanelController
public:
APMFlightModesComponentController
(
void
);
Q_PROPERTY
(
QString
modeParamPrefix
MEMBER
_modeParamPrefix
CONSTANT
)
Q_PROPERTY
(
QString
modeChannelParam
MEMBER
_modeChannelParam
CONSTANT
)
Q_PROPERTY
(
int
activeFlightMode
READ
activeFlightMode
NOTIFY
activeFlightModeChanged
)
Q_PROPERTY
(
int
channelCount
MEMBER
_channelCount
CONSTANT
)
Q_PROPERTY
(
QVariantList
channelOptionEnabled
READ
channelOptionEnabled
NOTIFY
channelOptionEnabledChanged
)
...
...
@@ -44,6 +46,8 @@ private slots:
void
_rcChannelsChanged
(
int
channelCount
,
int
pwmValues
[
Vehicle
::
cMaxRcChannels
]);
private:
QString
_modeParamPrefix
;
QString
_modeChannelParam
;
int
_activeFlightMode
;
int
_channelCount
;
QVariantList
_rgChannelOptionEnabled
;
...
...
src/AutoPilotPlugins/APM/APMFlightModesComponentSummary.qml
View file @
50089289
...
...
@@ -14,12 +14,14 @@ FactPanel {
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
enabled
}
FactPanelController
{
id
:
controller
;
factPanel
:
panel
}
property
Fact
flightMode1
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE1
"
)
property
Fact
flightMode2
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE2
"
)
property
Fact
flightMode3
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE3
"
)
property
Fact
flightMode4
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE4
"
)
property
Fact
flightMode5
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE5
"
)
property
Fact
flightMode6
:
controller
.
getParameterFact
(
-
1
,
"
FLTMODE6
"
)
property
var
_vehicle
:
controller
.
vehicle
property
Fact
flightMode1
:
controller
.
getParameterFact
(
-
1
,
_vehicle
.
rover
?
"
MODE1
"
:
"
FLTMODE1
"
)
property
Fact
flightMode2
:
controller
.
getParameterFact
(
-
1
,
_vehicle
.
rover
?
"
MODE2
"
:
"
FLTMODE2
"
)
property
Fact
flightMode3
:
controller
.
getParameterFact
(
-
1
,
_vehicle
.
rover
?
"
MODE3
"
:
"
FLTMODE3
"
)
property
Fact
flightMode4
:
controller
.
getParameterFact
(
-
1
,
_vehicle
.
rover
?
"
MODE4
"
:
"
FLTMODE4
"
)
property
Fact
flightMode5
:
controller
.
getParameterFact
(
-
1
,
_vehicle
.
rover
?
"
MODE5
"
:
"
FLTMODE5
"
)
property
Fact
flightMode6
:
controller
.
getParameterFact
(
-
1
,
_vehicle
.
rover
?
"
MODE6
"
:
"
FLTMODE6
"
)
Column
{
anchors.fill
:
parent
...
...
src/AutoPilotPlugins/APM/APMSensorsComponent.cc
View file @
50089289
...
...
@@ -117,13 +117,23 @@ bool APMSensorsComponent::compassSetupNeeded(void) const
bool
APMSensorsComponent
::
accelSetupNeeded
(
void
)
const
{
QStringList
offsets
;
offsets
<<
QStringLiteral
(
"INS_ACCOFFS_X"
)
<<
QStringLiteral
(
"INS_ACCOFFS_Y"
)
<<
QStringLiteral
(
"INS_ACCOFFS_Z"
);
foreach
(
const
QString
&
offset
,
offsets
)
{
if
(
_autopilot
->
getParameterFact
(
FactSystem
::
defaultComponentId
,
offset
)
->
rawValue
().
toFloat
()
==
0.0
f
)
{
return
true
;
const
size_t
cAccel
=
3
;
const
size_t
cOffset
=
3
;
QStringList
rgUse
;
QStringList
rgOffsets
[
cAccel
];
rgUse
<<
QStringLiteral
(
"INS_USE"
)
<<
QStringLiteral
(
"INS_USE2"
)
<<
QStringLiteral
(
"INS_USE3"
);
rgOffsets
[
0
]
<<
QStringLiteral
(
"INS_ACCOFFS_X"
)
<<
QStringLiteral
(
"INS_ACCOFFS_Y"
)
<<
QStringLiteral
(
"INS_ACCOFFS_Z"
);
rgOffsets
[
1
]
<<
QStringLiteral
(
"INS_ACC2OFFS_X"
)
<<
QStringLiteral
(
"INS_ACC2OFFS_Y"
)
<<
QStringLiteral
(
"INS_ACC2OFFS_Z"
);
rgOffsets
[
2
]
<<
QStringLiteral
(
"INS_ACC3OFFS_X"
)
<<
QStringLiteral
(
"INS_ACC3OFFS_Y"
)
<<
QStringLiteral
(
"INS_ACC3OFFS_Z"
);
for
(
size_t
i
=
0
;
i
<
cAccel
;
i
++
)
{
if
(
_autopilot
->
getParameterFact
(
FactSystem
::
defaultComponentId
,
rgUse
[
i
])
->
rawValue
().
toInt
()
!=
0
)
{
for
(
size_t
j
=
0
;
j
<
cOffset
;
j
++
)
{
if
(
_autopilot
->
getParameterFact
(
FactSystem
::
defaultComponentId
,
rgOffsets
[
i
][
j
])
->
rawValue
().
toFloat
()
==
0.0
f
)
{
return
true
;
}
}
}
}
...
...
src/FirmwarePlugin/APM/APMParameterMetaData.cc
View file @
50089289
...
...
@@ -88,7 +88,7 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum)
break
;
case
MAV_TYPE_GROUND_ROVER
:
case
MAV_TYPE_SURFACE_BOAT
:
vehicleName
=
"A
rduRover
"
;
vehicleName
=
"A
PMrover2
"
;
break
;
case
MAV_TYPE_SUBMARINE
:
vehicleName
=
"ArduSub"
;
...
...
src/Vehicle/Vehicle.cc
View file @
50089289
...
...
@@ -1405,6 +1405,11 @@ bool Vehicle::fixedWing(void) const
return
vehicleType
()
==
MAV_TYPE_FIXED_WING
;
}
bool
Vehicle
::
rover
(
void
)
const
{
return
vehicleType
()
==
MAV_TYPE_GROUND_ROVER
;
}
bool
Vehicle
::
multiRotor
(
void
)
const
{
switch
(
vehicleType
())
{
...
...
src/Vehicle/Vehicle.h
View file @
50089289
...
...
@@ -273,6 +273,7 @@ public:
Q_PROPERTY
(
bool
fixedWing
READ
fixedWing
CONSTANT
)
Q_PROPERTY
(
bool
multiRotor
READ
multiRotor
CONSTANT
)
Q_PROPERTY
(
bool
vtol
READ
vtol
CONSTANT
)
Q_PROPERTY
(
bool
rover
READ
rover
CONSTANT
)
Q_PROPERTY
(
bool
autoDisconnect
MEMBER
_autoDisconnect
NOTIFY
autoDisconnectChanged
)
Q_PROPERTY
(
QString
prearmError
READ
prearmError
WRITE
setPrearmError
NOTIFY
prearmErrorChanged
)
...
...
@@ -443,6 +444,7 @@ public:
bool
fixedWing
(
void
)
const
;
bool
multiRotor
(
void
)
const
;
bool
vtol
(
void
)
const
;
bool
rover
(
void
)
const
;
void
setFlying
(
bool
flying
);
void
setGuidedMode
(
bool
guidedMode
);
...
...
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