From 4e2dbb4a4ba1b17a05d8bf2555d7a53cbf3e7b37 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 13 Feb 2014 17:11:57 +1100 Subject: [PATCH] Rover: change to new board_voltage() API --- APMrover2/APMrover2.pde | 3 --- APMrover2/GCS_Mavlink.pde | 2 +- APMrover2/Log.pde | 2 +- APMrover2/system.pde | 8 -------- 4 files changed, 2 insertions(+), 13 deletions(-) diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index b99954ad2e..1e4da0cf44 100644 --- a/APMrover2/APMrover2.pde +++ b/APMrover2/APMrover2.pde @@ -282,8 +282,6 @@ static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS]; // is to take the 0 to 1024 range down to an 8 bit range for MAVLink AP_HAL::AnalogSource *rssi_analog_source; -AP_HAL::AnalogSource *vcc_pin; - //////////////////////////////////////////////////////////////////////////////// // SONAR selection //////////////////////////////////////////////////////////////////////////////// @@ -590,7 +588,6 @@ void setup() { battery.init(); rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE); - vcc_pin = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC); init_ardupilot(); diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index 24fab18e8b..ee72e87646 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -422,7 +422,7 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan) { mavlink_msg_hwstatus_send( chan, - board_voltage(), + hal.analogin->board_voltage()*1000, hal.i2c->lockup_count()); } diff --git a/APMrover2/Log.pde b/APMrover2/Log.pde index 56911b0c19..a8d329e912 100644 --- a/APMrover2/Log.pde +++ b/APMrover2/Log.pde @@ -450,7 +450,7 @@ static void Log_Write_Current() throttle_in : channel_throttle->control_in, battery_voltage : (int16_t)(battery.voltage() * 100.0), current_amps : (int16_t)(battery.current_amps() * 100.0), - board_voltage : board_voltage(), + board_voltage : (uint16_t)(hal.analogin->board_voltage()*1000), current_total : battery.current_total_mah() }; DataFlash.WriteBlock(&pkt, sizeof(pkt)); diff --git a/APMrover2/system.pde b/APMrover2/system.pde index 888e591cf6..5a01a7e3ad 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -449,14 +449,6 @@ static void check_usb_mux(void) } -/* - * Read board voltage in millivolts - */ -uint16_t board_voltage(void) -{ - return vcc_pin->voltage_latest() * 1000; -} - static void print_mode(AP_HAL::BetterStream *port, uint8_t mode) {