From f486d8427189f1de3aae16999f7c80f032764a81 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sun, 17 Jul 2011 19:08:17 +0000 Subject: [PATCH] 2.0.37 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 --- ArduCopterMega/Mavlink_Common.h | 4 ++-- ArduCopterMega/test.pde | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopterMega/Mavlink_Common.h b/ArduCopterMega/Mavlink_Common.h index ea1bae729e..976a4bdb99 100644 --- a/ArduCopterMega/Mavlink_Common.h +++ b/ArduCopterMega/Mavlink_Common.h @@ -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; } diff --git a/ArduCopterMega/test.pde b/ArduCopterMega/test.pde index 0afa8cf085..a455f1636e 100644 --- a/ArduCopterMega/test.pde +++ b/ArduCopterMega/test.pde @@ -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);