Added rate of change limit for noisy Sonars.
converted to static functions - Tridge


git-svn-id: https://arducopter.googlecode.com/svn/trunk@2901 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-07-17 19:08:17 +00:00
parent de76785499
commit f486d84271
2 changed files with 3 additions and 2 deletions

View File

@ -201,9 +201,9 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
motor_out[2],
motor_out[3],
motor_out[4],
motor_out[5],
motor_out[6],
motor_out[7],
0);
motor_out[7]);
break;
}

View File

@ -960,6 +960,7 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
delay(100);
Serial.printf_P(PSTR("Sonar: %d cm\n"), sonar.read());
//Serial.printf_P(PSTR("Sonar, %d, %d\n"), sonar.read(), sonar.raw_value);
if(Serial.available() > 0){
return (0);