Commit a1ab4e89 authored by DonLakeFlyer's avatar DonLakeFlyer

PID tuning fixes

parent 9b7cfd25
......@@ -123,6 +123,7 @@ SetupPage {
property real _valueRateSetpoint
readonly property int _tickSeparation: 5
readonly property int _maxTickSections: 10
readonly property int _tuneListRollIndex: 0
readonly property int _tuneListPitchIndex: 1
readonly property int _tuneListYawIndex: 2
......@@ -267,7 +268,7 @@ SetupPage {
min: 0
max: 10
titleText: "deg"
tickCount: ((max - min) / _tickSeparation) + 1
tickCount: Math.min(((max - min) / _tickSeparation), _maxTickSections) + 1
}
ValueAxis {
......@@ -275,12 +276,12 @@ SetupPage {
min: 0
max: 10
titleText: "deg/s"
tickCount: ((max - min) / _tickSeparation) + 1
tickCount: Math.min(((max - min) / _tickSeparation), _maxTickSections) + 1
}
Timer {
id: dataTimer
interval: 50
interval: 10
running: false
repeat: true
......@@ -308,6 +309,8 @@ SetupPage {
adjustYAxisMax(_valueRateYAxis, _valueRateSetpoint)
_msecs += interval
/*
Testing with just start/stop for now. No time limit.
if (valueSeries.count > _maxPointCount) {
valueSeries.remove(0)
valueSetpointSeries.remove(0)
......@@ -316,6 +319,7 @@ SetupPage {
valueXAxis.min = valueSeries.at(0).x
valueRateXAxis.min = valueSeries.at(0).x
}
*/
}
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
......
......@@ -788,9 +788,9 @@ void Vehicle::_handleAttitudeTarget(mavlink_message_t& message)
float roll, pitch, yaw;
mavlink_quaternion_to_euler(attitudeTarget.q, &roll, &pitch, &yaw);
_setpointFactGroup.roll()->setRawValue(roll);
_setpointFactGroup.pitch()->setRawValue(pitch);
_setpointFactGroup.yaw()->setRawValue(yaw);
_setpointFactGroup.roll()->setRawValue(qRadiansToDegrees(roll));
_setpointFactGroup.pitch()->setRawValue(qRadiansToDegrees(pitch));
_setpointFactGroup.yaw()->setRawValue(qRadiansToDegrees(yaw));
_setpointFactGroup.rollRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_roll_rate));
_setpointFactGroup.pitchRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_pitch_rate));
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment