mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
doubled Slew rate limiter to 2 m/s max @ 10 hz.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2912 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
98980d6f61
commit
c79ff4f583
@ -88,9 +88,9 @@ int RangeFinder::read()
|
||||
|
||||
// slew rate
|
||||
if(raw_value > distance){
|
||||
temp_dist = min(distance + 10, raw_value);
|
||||
temp_dist = min(distance + 20, raw_value);
|
||||
}else{
|
||||
temp_dist = max(distance - 10, raw_value);
|
||||
temp_dist = max(distance - 20, raw_value);
|
||||
}
|
||||
|
||||
if(_num_averages > 0){
|
||||
|
Loading…
Reference in New Issue
Block a user