Rover: change to new board_voltage() API

This commit is contained in:
Andrew Tridgell 2014-02-13 17:11:57 +11:00
parent 043c80dbe6
commit 4e2dbb4a4b
4 changed files with 2 additions and 13 deletions

View File

@ -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();

View File

@ -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());
}

View File

@ -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));

View File

@ -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)
{