mirror of https://github.com/ArduPilot/ardupilot
Tracker: use pitch-min and pitch-max in place of constants
This commit is contained in:
parent
a967caa924
commit
836adb6b0b
|
@ -16,7 +16,7 @@ void Tracker::update_auto(void)
|
|||
}
|
||||
|
||||
float yaw = wrap_180_cd((nav_status.bearing+g.yaw_trim)*100); // target yaw in centidegrees
|
||||
float pitch = constrain_float(nav_status.pitch+g.pitch_trim, -90, 90) * 100; // target pitch in centidegrees
|
||||
float pitch = constrain_float(nav_status.pitch+g.pitch_trim, g.pitch_min, g.pitch_max) * 100; // target pitch in centidegrees
|
||||
|
||||
bool direction_reversed = get_ef_yaw_direction();
|
||||
|
||||
|
|
|
@ -25,13 +25,13 @@ void Tracker::update_scan(void)
|
|||
if (!nav_status.manual_control_pitch) {
|
||||
float pitch_delta = g.scan_speed_pitch * 0.02f;
|
||||
nav_status.pitch += pitch_delta * (nav_status.scan_reverse_pitch?-1:1);
|
||||
if (nav_status.pitch < -90 && nav_status.scan_reverse_pitch) {
|
||||
if (nav_status.pitch < g.pitch_min && nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = false;
|
||||
}
|
||||
if (nav_status.pitch > 90 && !nav_status.scan_reverse_pitch) {
|
||||
if (nav_status.pitch > g.pitch_max && !nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = true;
|
||||
}
|
||||
nav_status.pitch = constrain_float(nav_status.pitch, -90, 90);
|
||||
nav_status.pitch = constrain_float(nav_status.pitch, -g.pitch_min, g.pitch_max);
|
||||
}
|
||||
|
||||
update_auto();
|
||||
|
|
Loading…
Reference in New Issue