mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
added param for crosstrack gain defaulted to 4
This commit is contained in:
parent
9bc4328724
commit
39d0df4cef
@ -215,7 +215,7 @@ static void update_crosstrack(void)
|
||||
//radians((target_bearing - original_target_bearing) / 100)
|
||||
crosstrack_error = sin(temp) * wp_distance; // Meters we are off track line
|
||||
|
||||
crosstrack_error = constrain(crosstrack_error * 4, -1200, 1200);
|
||||
crosstrack_error = constrain(crosstrack_error * g.crosstrack_gain, -1200, 1200);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user