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
dab6ec1f
Commit
dab6ec1f
authored
May 02, 2019
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
aeff1d97
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
124 additions
and
50 deletions
+124
-50
PIDTuning.qml
src/QmlControls/PIDTuning.qml
+52
-36
Vehicle.cc
src/Vehicle/Vehicle.cc
+64
-14
Vehicle.h
src/Vehicle/Vehicle.h
+8
-0
No files found.
src/QmlControls/PIDTuning.qml
View file @
dab6ec1f
...
...
@@ -146,7 +146,7 @@ RowLayout {
saveTuningParamValues
()
}
Component.onDestruction
:
_activeVehicle
.
setPIDTuningTelemetryMode
(
tru
e
)
Component.onDestruction
:
_activeVehicle
.
setPIDTuningTelemetryMode
(
fals
e
)
on_CurrentTuneTypeChanged
:
{
saveTuningParamValues
()
...
...
@@ -197,14 +197,6 @@ RowLayout {
running
:
false
repeat
:
true
function
startOrStop
()
{
if
(
dataTimer
.
running
)
{
dataTimer
.
stop
()
}
else
{
dataTimer
.
start
()
}
}
onTriggered
:
{
_valueXAxis
.
max
=
_msecs
_valueRateXAxis
.
max
=
_msecs
...
...
@@ -238,25 +230,25 @@ RowLayout {
spacing
:
_margins
Layout.alignment
:
Qt
.
AlignTop
QGCLabel
{
text
:
qsTr
(
"
Tuning Axis:
"
)
}
Column
{
QGCLabel
{
text
:
qsTr
(
"
Tuning Axis:
"
)
}
RowLayout
{
spacing
:
_margins
RowLayout
{
spacing
:
_margins
Repeater
{
model
:
tuneList
QGCRadioButton
{
text
:
modelData
checked
:
_currentTuneType
===
modelData
exclusiveGroup
:
tuneTypeRadios
Repeater
{
model
:
tuneList
QGCRadioButton
{
text
:
modelData
checked
:
_currentTuneType
===
modelData
exclusiveGroup
:
tuneTypeRadios
onClicked
:
_currentTuneType
=
modelData
onClicked
:
_currentTuneType
=
modelData
}
}
}
}
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Tuning Values:
"
)
}
GridLayout
{
...
...
@@ -328,26 +320,27 @@ RowLayout {
}
}
}
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Clipboard Values:
"
)
}
Column
{
QGCLabel
{
text
:
qsTr
(
"
Clipboard Values:
"
)
}
GridLayout
{
rows
:
savedRepeater
.
model
.
length
flow
:
GridLayout
.
TopToBottom
rowSpacing
:
_margins
columnSpacing
:
_margins
GridLayout
{
rows
:
savedRepeater
.
model
.
length
flow
:
GridLayout
.
TopToBottom
rowSpacing
:
0
columnSpacing
:
_margins
Repeater
{
model
:
params
[
tuneList
.
indexOf
(
_currentTuneType
)]
Repeater
{
model
:
params
[
tuneList
.
indexOf
(
_currentTuneType
)]
QGCLabel
{
text
:
modelData
.
name
}
}
QGCLabel
{
text
:
modelData
.
name
}
}
Repeater
{
id
:
savedRepeater
Repeater
{
id
:
savedRepeater
QGCLabel
{
text
:
modelData
}
QGCLabel
{
text
:
modelData
}
}
}
}
...
...
@@ -379,7 +372,30 @@ RowLayout {
QGCButton
{
text
:
dataTimer
.
running
?
qsTr
(
"
Stop
"
)
:
qsTr
(
"
Start
"
)
onClicked
:
dataTimer
.
startOrStop
()
onClicked
:
{
dataTimer
.
running
=
!
dataTimer
.
running
if
(
autoModeChange
.
checked
)
{
_activeVehicle
.
flightMode
=
dataTimer
.
running
?
"
Stabilized
"
:
_activeVehicle
.
pauseFlightMode
}
}
}
}
QGCCheckBox
{
id
:
autoModeChange
text
:
qsTr
(
"
Automatic Flight Mode Switching
"
)
}
Column
{
visible
:
autoModeChange
.
checked
QGCLabel
{
text
:
qsTr
(
"
Switches to 'Stabilized' when you click Start.
"
)
font.pointSize
:
ScreenTools
.
smallFontPointSize
}
QGCLabel
{
text
:
qsTr
(
"
Switches to '%1' when you click Stop.
"
).
arg
(
_activeVehicle
.
pauseFlightMode
)
font.pointSize
:
ScreenTools
.
smallFontPointSize
}
}
}
...
...
src/Vehicle/Vehicle.cc
View file @
dab6ec1f
...
...
@@ -185,6 +185,8 @@ Vehicle::Vehicle(LinkInterface* link,
,
_lastAnnouncedLowBatteryPercent
(
100
)
,
_priorityLinkCommanded
(
false
)
,
_orbitActive
(
false
)
,
_pidTuningTelemetryMode
(
false
)
,
_pidTuningWaitingForRates
(
false
)
,
_rollFact
(
0
,
_rollFactName
,
FactMetaData
::
valueTypeDouble
)
,
_pitchFact
(
0
,
_pitchFactName
,
FactMetaData
::
valueTypeDouble
)
,
_headingFact
(
0
,
_headingFactName
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -386,6 +388,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_uid
(
0
)
,
_lastAnnouncedLowBatteryPercent
(
100
)
,
_orbitActive
(
false
)
,
_pidTuningTelemetryMode
(
false
)
,
_pidTuningWaitingForRates
(
false
)
,
_rollFact
(
0
,
_rollFactName
,
FactMetaData
::
valueTypeDouble
)
,
_pitchFact
(
0
,
_pitchFactName
,
FactMetaData
::
valueTypeDouble
)
,
_headingFact
(
0
,
_headingFactName
,
FactMetaData
::
valueTypeDouble
)
...
...
@@ -519,6 +523,8 @@ void Vehicle::_commonInit(void)
}
}
#endif
_pidTuningMessages
<<
MAVLINK_MSG_ID_ATTITUDE
<<
MAVLINK_MSG_ID_ATTITUDE_TARGET
;
}
Vehicle
::~
Vehicle
()
...
...
@@ -794,7 +800,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case
MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS
:
_handleOrbitExecutionStatus
(
message
);
break
;
case
MAVLINK_MSG_ID_MESSAGE_INTERVAL
:
_handleMessageInterval
(
message
);
break
;
case
MAVLINK_MSG_ID_PING
:
_handlePing
(
link
,
message
);
break
;
...
...
@@ -3859,29 +3867,71 @@ int Vehicle::versionCompare(int major, int minor, int patch)
return
_firmwarePlugin
->
versionCompare
(
this
,
major
,
minor
,
patch
);
}
void
Vehicle
::
setPIDTuningTelemetryMode
(
bool
pidTuning
)
void
Vehicle
::
_handleMessageInterval
(
const
mavlink_message_t
&
message
)
{
qDebug
()
<<
"setPIDTuningTelemetryMode"
<<
pidTuning
;
QList
<
int
>
rgTelemetry
;
if
(
_pidTuningWaitingForRates
)
{
mavlink_message_interval_t
messageInterval
;
mavlink_msg_message_interval_decode
(
&
message
,
&
messageInterval
);
int
msgId
=
messageInterval
.
message_id
;
if
(
_pidTuningMessages
.
contains
(
msgId
))
{
_pidTuningMessageRatesUsecs
[
msgId
]
=
messageInterval
.
interval_us
;
}
if
(
_pidTuningMessageRatesUsecs
.
count
()
==
_pidTuningMessages
.
count
())
{
// We have back all the rates we requested
_pidTuningWaitingForRates
=
false
;
_pidTuningAdjustRates
(
true
);
}
}
}
void
Vehicle
::
setPIDTuningTelemetryMode
(
bool
pidTuning
)
{
if
(
pidTuning
)
{
rgTelemetry
<<
MAVLINK_MSG_ID_ATTITUDE
<<
MAVLINK_MSG_ID_ATTITUDE_TARGET
;
for
(
int
telemetry
:
rgTelemetry
)
{
if
(
!
_pidTuningTelemetryMode
)
{
// First step is to get the current message rates before we adjust them
_pidTuningTelemetryMode
=
true
;
_pidTuningWaitingForRates
=
true
;
_pidTuningMessageRatesUsecs
.
clear
();
for
(
int
telemetry
:
_pidTuningMessages
)
{
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_GET_MESSAGE_INTERVAL
,
true
,
// show error
telemetry
);
}
}
}
else
{
if
(
_pidTuningTelemetryMode
)
{
_pidTuningTelemetryMode
=
false
;
if
(
_pidTuningWaitingForRates
)
{
// We never finished waiting for previous rates
_pidTuningWaitingForRates
=
false
;
}
else
{
_pidTuningAdjustRates
(
false
);
}
}
}
}
void
Vehicle
::
_pidTuningAdjustRates
(
bool
setRatesForTuning
)
{
int
requestedRate
=
(
int
)(
1000000.0
/
30.0
);
// 30 Hz in usecs
for
(
int
telemetry
:
_pidTuningMessages
)
{
if
(
requestedRate
<
_pidTuningMessageRatesUsecs
[
telemetry
])
{
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_SET_MESSAGE_INTERVAL
,
true
,
// show error
telemetry
,
pidTuning
?
(
1000000.0
/
30.0
)
/* Hz */
:
-
1
/* default Hz */
);
setRatesForTuning
?
requestedRate
:
_pidTuningMessageRatesUsecs
[
telemetry
]
);
}
}
setLiveUpdates
(
pidTuning
);
_setpointFactGroup
.
setLiveUpdates
(
pidTuning
);
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_GET_MESSAGE_INTERVAL
,
true
,
// show error
MAVLINK_MSG_ID_ATTITUDE
);
setLiveUpdates
(
setRatesForTuning
);
_setpointFactGroup
.
setLiveUpdates
(
setRatesForTuning
);
}
...
...
src/Vehicle/Vehicle.h
View file @
dab6ec1f
...
...
@@ -1267,6 +1267,7 @@ private:
void
_handleEstimatorStatus
(
mavlink_message_t
&
message
);
void
_handleStatusText
(
mavlink_message_t
&
message
,
bool
longVersion
);
void
_handleOrbitExecutionStatus
(
const
mavlink_message_t
&
message
);
void
_handleMessageInterval
(
const
mavlink_message_t
&
message
);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void
_handleCameraFeedback
(
const
mavlink_message_t
&
message
);
...
...
@@ -1293,6 +1294,7 @@ private:
void
_setCapabilities
(
uint64_t
capabilityBits
);
void
_updateArmed
(
bool
armed
);
bool
_apmArmingNotRequired
(
void
);
void
_pidTuningAdjustRates
(
bool
setRatesForTuning
);
int
_id
;
///< Mavlink system id
int
_defaultComponentId
;
...
...
@@ -1475,6 +1477,12 @@ private:
QTimer
_orbitTelemetryTimer
;
static
const
int
_orbitTelemetryTimeoutMsecs
=
3000
;
// No telemetry for this amount and orbit will go inactive
// PID Tuning telemetry mode
bool
_pidTuningTelemetryMode
;
bool
_pidTuningWaitingForRates
;
QList
<
int
>
_pidTuningMessages
;
QMap
<
int
,
int
>
_pidTuningMessageRatesUsecs
;
// FactGroup facts
Fact
_rollFact
;
...
...
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