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
59be6d63
Commit
59be6d63
authored
Jun 11, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Support preflight barometer calibration
parent
21090040
Changes
10
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
102 additions
and
147 deletions
+102
-147
APMSensorsComponent.qml
src/AutoPilotPlugins/APM/APMSensorsComponent.qml
+97
-87
APMSensorsComponentController.cc
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
+4
-24
APMSensorsComponentController.h
src/AutoPilotPlugins/APM/APMSensorsComponentController.h
+1
-12
RadioComponent.qml
src/AutoPilotPlugins/Common/RadioComponent.qml
+0
-1
ArduSubFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc
+0
-5
ArduSubFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h
+0
-2
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+0
-5
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+0
-4
Vehicle.cc
src/Vehicle/Vehicle.cc
+0
-5
Vehicle.h
src/Vehicle/Vehicle.h
+0
-2
No files found.
src/AutoPilotPlugins/APM/APMSensorsComponent.qml
View file @
59be6d63
This diff is collapsed.
Click to expand it.
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
View file @
59be6d63
...
...
@@ -27,14 +27,8 @@ APMSensorsComponentController::APMSensorsComponentController(void)
:
_sensorsComponent
(
NULL
)
,
_statusLog
(
NULL
)
,
_progressBar
(
NULL
)
,
_compassButton
(
NULL
)
,
_accelButton
(
NULL
)
,
_compassMotButton
(
NULL
)
,
_levelButton
(
NULL
)
,
_calibratePressureButton
(
NULL
)
,
_nextButton
(
NULL
)
,
_cancelButton
(
NULL
)
,
_setOrientationsButton
(
NULL
)
,
_showOrientationCalArea
(
false
)
,
_calTypeInProgress
(
CalTypeNone
)
,
_orientationCalDownSideDone
(
false
)
...
...
@@ -110,12 +104,7 @@ void APMSensorsComponentController::_startLogCalibration(void)
connect
(
_uas
,
&
UASInterface
::
textMessageReceived
,
this
,
&
APMSensorsComponentController
::
_handleUASTextMessage
);
_compassButton
->
setEnabled
(
false
);
_accelButton
->
setEnabled
(
false
);
_compassMotButton
->
setEnabled
(
false
);
_levelButton
->
setEnabled
(
false
);
_calibratePressureButton
->
setEnabled
(
false
);
_setOrientationsButton
->
setEnabled
(
false
);
emit
setAllCalButtonsEnabled
(
false
);
if
(
_calTypeInProgress
==
CalTypeAccel
||
_calTypeInProgress
==
CalTypeCompassMot
)
{
_nextButton
->
setEnabled
(
true
);
}
...
...
@@ -124,13 +113,9 @@ void APMSensorsComponentController::_startLogCalibration(void)
void
APMSensorsComponentController
::
_startVisualCalibration
(
void
)
{
_compassButton
->
setEnabled
(
false
);
_accelButton
->
setEnabled
(
false
);
_compassMotButton
->
setEnabled
(
false
);
_levelButton
->
setEnabled
(
false
);
_calibratePressureButton
->
setEnabled
(
false
);
_setOrientationsButton
->
setEnabled
(
false
);
emit
setAllCalButtonsEnabled
(
false
);
_cancelButton
->
setEnabled
(
true
);
_nextButton
->
setEnabled
(
false
);
_resetInternalState
();
...
...
@@ -169,12 +154,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
disconnect
(
_uas
,
&
UASInterface
::
textMessageReceived
,
this
,
&
APMSensorsComponentController
::
_handleUASTextMessage
);
_compassButton
->
setEnabled
(
true
);
_accelButton
->
setEnabled
(
true
);
_compassMotButton
->
setEnabled
(
true
);
_levelButton
->
setEnabled
(
true
);
_calibratePressureButton
->
setEnabled
(
true
);
_setOrientationsButton
->
setEnabled
(
true
);
emit
setAllCalButtonsEnabled
(
true
);
_nextButton
->
setEnabled
(
false
);
_cancelButton
->
setEnabled
(
false
);
...
...
src/AutoPilotPlugins/APM/APMSensorsComponentController.h
View file @
59be6d63
...
...
@@ -34,14 +34,8 @@ public:
Q_PROPERTY
(
QQuickItem
*
statusLog
MEMBER
_statusLog
)
Q_PROPERTY
(
QQuickItem
*
progressBar
MEMBER
_progressBar
)
Q_PROPERTY
(
QQuickItem
*
compassButton
MEMBER
_compassButton
)
Q_PROPERTY
(
QQuickItem
*
accelButton
MEMBER
_accelButton
)
Q_PROPERTY
(
QQuickItem
*
compassMotButton
MEMBER
_compassMotButton
)
Q_PROPERTY
(
QQuickItem
*
levelButton
MEMBER
_levelButton
)
Q_PROPERTY
(
QQuickItem
*
calibratePressureButton
MEMBER
_calibratePressureButton
)
Q_PROPERTY
(
QQuickItem
*
nextButton
MEMBER
_nextButton
)
Q_PROPERTY
(
QQuickItem
*
cancelButton
MEMBER
_cancelButton
)
Q_PROPERTY
(
QQuickItem
*
setOrientationsButton
MEMBER
_setOrientationsButton
)
Q_PROPERTY
(
QQuickItem
*
orientationCalAreaHelpText
MEMBER
_orientationCalAreaHelpText
)
Q_PROPERTY
(
bool
compassSetupNeeded
READ
compassSetupNeeded
NOTIFY
setupNeededChanged
)
...
...
@@ -135,6 +129,7 @@ signals:
void
compass1CalFitnessChanged
(
double
compass1CalFitness
);
void
compass2CalFitnessChanged
(
double
compass2CalFitness
);
void
compass3CalFitnessChanged
(
double
compass3CalFitness
);
void
setAllCalButtonsEnabled
(
bool
enabled
);
private
slots
:
void
_handleUASTextMessage
(
int
uasId
,
int
compId
,
int
severity
,
QString
text
);
...
...
@@ -168,14 +163,8 @@ private:
QQuickItem
*
_statusLog
;
QQuickItem
*
_progressBar
;
QQuickItem
*
_compassButton
;
QQuickItem
*
_accelButton
;
QQuickItem
*
_compassMotButton
;
QQuickItem
*
_levelButton
;
QQuickItem
*
_calibratePressureButton
;
QQuickItem
*
_nextButton
;
QQuickItem
*
_cancelButton
;
QQuickItem
*
_setOrientationsButton
;
QQuickItem
*
_orientationCalAreaHelpText
;
bool
_showOrientationCalArea
;
...
...
src/AutoPilotPlugins/Common/RadioComponent.qml
View file @
59be6d63
...
...
@@ -418,7 +418,6 @@ SetupPage {
QGCButton
{
text
:
qsTr
(
"
Copy Trims
"
)
visible
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
.
px4Firmware
onClicked
:
showDialog
(
copyTrimsDialogComponent
,
dialogTitle
,
radioPage
.
showDialogDefaultWidth
,
StandardButton
.
Ok
|
StandardButton
.
Cancel
)
}
...
...
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc
View file @
59be6d63
...
...
@@ -132,11 +132,6 @@ bool ArduSubFirmwarePlugin::supportsJSButton(void)
return
true
;
}
bool
ArduSubFirmwarePlugin
::
supportsCalibratePressure
(
void
)
{
return
true
;
}
bool
ArduSubFirmwarePlugin
::
supportsMotorInterference
(
void
)
{
return
false
;
...
...
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h
View file @
59be6d63
...
...
@@ -79,8 +79,6 @@ public:
bool
supportsJSButton
(
void
);
bool
supportsCalibratePressure
(
void
);
bool
supportsMotorInterference
(
void
);
QString
brandImageIndoor
(
const
Vehicle
*
vehicle
)
const
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/APM/BrandImageSub"
);
}
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
59be6d63
...
...
@@ -139,11 +139,6 @@ bool FirmwarePlugin::supportsRadio(void)
return
true
;
}
bool
FirmwarePlugin
::
supportsCalibratePressure
(
void
)
{
return
false
;
}
bool
FirmwarePlugin
::
supportsMotorInterference
(
void
)
{
return
true
;
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
59be6d63
...
...
@@ -170,10 +170,6 @@ public:
/// to be assigned via parameters in firmware. Default is false.
virtual
bool
supportsJSButton
(
void
);
/// Returns true if the firmware supports calibrating the pressure sensor so the altitude will read
/// zero at the current pressure. Default is false.
virtual
bool
supportsCalibratePressure
(
void
);
/// Returns true if the firmware supports calibrating motor interference offsets for the compass
/// (CompassMot). Default is true.
virtual
bool
supportsMotorInterference
(
void
);
...
...
src/Vehicle/Vehicle.cc
View file @
59be6d63
...
...
@@ -1959,11 +1959,6 @@ bool Vehicle::supportsJSButton(void) const
return
_firmwarePlugin
->
supportsJSButton
();
}
bool
Vehicle
::
supportsCalibratePressure
(
void
)
const
{
return
_firmwarePlugin
->
supportsCalibratePressure
();
}
bool
Vehicle
::
supportsMotorInterference
(
void
)
const
{
return
_firmwarePlugin
->
supportsMotorInterference
();
...
...
src/Vehicle/Vehicle.h
View file @
59be6d63
...
...
@@ -282,7 +282,6 @@ public:
Q_PROPERTY
(
bool
supportsThrottleModeCenterZero
READ
supportsThrottleModeCenterZero
CONSTANT
)
Q_PROPERTY
(
bool
supportsJSButton
READ
supportsJSButton
CONSTANT
)
Q_PROPERTY
(
bool
supportsRadio
READ
supportsRadio
CONSTANT
)
Q_PROPERTY
(
bool
supportsCalibratePressure
READ
supportsCalibratePressure
CONSTANT
)
Q_PROPERTY
(
bool
supportsMotorInterference
READ
supportsMotorInterference
CONSTANT
)
Q_PROPERTY
(
bool
autoDisconnect
MEMBER
_autoDisconnect
NOTIFY
autoDisconnectChanged
)
Q_PROPERTY
(
QString
prearmError
READ
prearmError
WRITE
setPrearmError
NOTIFY
prearmErrorChanged
)
...
...
@@ -519,7 +518,6 @@ public:
bool
supportsThrottleModeCenterZero
(
void
)
const
;
bool
supportsRadio
(
void
)
const
;
bool
supportsJSButton
(
void
)
const
;
bool
supportsCalibratePressure
(
void
)
const
;
bool
supportsMotorInterference
(
void
)
const
;
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