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
98565fdb
Unverified
Commit
98565fdb
authored
Jun 25, 2018
by
Don Gagne
Committed by
GitHub
Jun 25, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6654 from DonLakeFlyer/ArduPilotReboot
Ardu pilot reboot
parents
35d09c3c
bc829486
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
37 additions
and
6 deletions
+37
-6
APMSensorsComponent.qml
src/AutoPilotPlugins/APM/APMSensorsComponent.qml
+35
-5
Vehicle.cc
src/Vehicle/Vehicle.cc
+1
-0
LinkInterface.cc
src/comm/LinkInterface.cc
+1
-1
No files found.
src/AutoPilotPlugins/APM/APMSensorsComponent.qml
View file @
98565fdb
...
...
@@ -37,8 +37,8 @@ SetupPage {
// Help text which is shown both in the status text area prior to pressing a cal button and in the
// pre-calibration dialog.
readonly
property
string
orientationHelpSet
:
qsTr
(
"
If
the orientation is
in the direction of flight, select None.
"
)
readonly
property
string
orientationHelpCal
:
qsTr
(
"
Before calibrating make sure
orien
tation settings are correct.
"
)
+
orientationHelpSet
readonly
property
string
orientationHelpSet
:
qsTr
(
"
If
mounted
in the direction of flight, select None.
"
)
readonly
property
string
orientationHelpCal
:
qsTr
(
"
Before calibrating make sure
ro
tation settings are correct.
"
)
+
orientationHelpSet
readonly
property
string
compassRotationText
:
qsTr
(
"
If the compass or GPS module is mounted in flight direction, leave the default value (None)
"
)
readonly
property
string
compassHelp
:
qsTr
(
"
For Compass calibration you will need to rotate your vehicle through a number of positions.
"
)
...
...
@@ -137,10 +137,10 @@ SetupPage {
onCalibrationComplete
:
{
switch
(
calType
)
{
case
APMSensorsComponentController.CalTypeAccel
:
show
Message
(
qsTr
(
"
Calibration complete
"
),
qsTr
(
"
Accelerometer calibration complete.
"
)
,
StandardButton
.
Ok
)
show
Dialog
(
postCalibrationComponent
,
qsTr
(
"
Accelerometer calibration complete
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Ok
)
break
case
APMSensorsComponentController.CalTypeOffboardCompass
:
show
Message
(
qsTr
(
"
Calibration complete
"
),
qsTr
(
"
Compass calibration complete.
"
)
,
StandardButton
.
Ok
)
show
Dialog
(
postCalibrationComponent
,
qsTr
(
"
Compass calibration complete
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Ok
)
break
case
APMSensorsComponentController.CalTypeOnboardCompass
:
showDialog
(
postOnboardCompassCalibrationComponent
,
qsTr
(
"
Calibration complete
"
),
qgcView
.
showDialogDefaultWidth
,
StandardButton
.
Ok
)
...
...
@@ -262,6 +262,36 @@ SetupPage {
qsTr
(
"
- Red indicates a compass which should not be used.
\n\n
"
)
+
qsTr
(
"
YOU MUST REBOOT YOUR VEHICLE AFTER EACH CALIBRATION.
"
)
}
QGCButton
{
text
:
qsTr
(
"
Reboot Vehicle
"
)
onClicked
:
controller
.
vehicle
.
reboot
()
}
}
}
}
Component
{
id
:
postCalibrationComponent
QGCViewDialog
{
Column
{
anchors.margins
:
ScreenTools
.
defaultFontPixelWidth
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelHeight
QGCLabel
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
wrapMode
:
Text
.
WordWrap
text
:
qsTr
(
"
YOU MUST REBOOT YOUR VEHICLE AFTER EACH CALIBRATION.
"
)
}
QGCButton
{
text
:
qsTr
(
"
Reboot Vehicle
"
)
onClicked
:
controller
.
vehicle
.
rebootVehicle
()
}
}
}
}
...
...
@@ -343,7 +373,7 @@ SetupPage {
}
Column
{
QGCLabel
{
text
:
qsTr
(
"
Autopilot
Orien
tation:
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Autopilot
Ro
tation:
"
)
}
FactComboBox
{
width
:
rotationColumnWidth
...
...
src/Vehicle/Vehicle.cc
View file @
98565fdb
...
...
@@ -3139,6 +3139,7 @@ QString Vehicle::firmwareVersionTypeString(void) const
void
Vehicle
::
rebootVehicle
()
{
_autoDisconnect
=
true
;
sendMavCommand
(
_defaultComponentId
,
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
,
true
,
1.0
f
);
}
...
...
src/comm/LinkInterface.cc
View file @
98565fdb
...
...
@@ -204,7 +204,7 @@ void LinkInterface::stopHeartbeatTimer() {
while
(
iter
.
hasNext
())
{
iter
.
next
();
QObject
::
disconnect
(
iter
.
value
(),
&
HeartbeatTimer
::
activeChanged
,
this
,
&
LinkInterface
::
_activeChanged
);
delete
_heartbeatTimers
[
iter
.
key
()]
;
_heartbeatTimers
[
iter
.
key
()]
->
deleteLater
()
;
_heartbeatTimers
[
iter
.
key
()]
=
nullptr
;
}
...
...
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