Plane: use new board_voltage() method
This commit is contained in:
parent
1849db7074
commit
043c80dbe6
@ -314,8 +314,6 @@ static AP_SpdHgtControl *SpdHgt_Controller = &TECS_controller;
|
|||||||
// a pin for reading the receiver RSSI voltage.
|
// a pin for reading the receiver RSSI voltage.
|
||||||
static AP_HAL::AnalogSource *rssi_analog_source;
|
static AP_HAL::AnalogSource *rssi_analog_source;
|
||||||
|
|
||||||
static AP_HAL::AnalogSource *vcc_pin;
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Sonar
|
// Sonar
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -757,8 +755,6 @@ void setup() {
|
|||||||
|
|
||||||
rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
|
rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
|
||||||
|
|
||||||
vcc_pin = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
|
|
||||||
|
|
||||||
init_ardupilot();
|
init_ardupilot();
|
||||||
|
|
||||||
// initialise the main loop scheduler
|
// initialise the main loop scheduler
|
||||||
|
@ -532,7 +532,7 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
|||||||
{
|
{
|
||||||
mavlink_msg_hwstatus_send(
|
mavlink_msg_hwstatus_send(
|
||||||
chan,
|
chan,
|
||||||
board_voltage(),
|
hal.analogin->board_voltage()*1000,
|
||||||
hal.i2c->lockup_count());
|
hal.i2c->lockup_count());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -441,7 +441,7 @@ static void Log_Write_Current()
|
|||||||
throttle_in : channel_throttle->control_in,
|
throttle_in : channel_throttle->control_in,
|
||||||
battery_voltage : (int16_t)(battery.voltage() * 100.0),
|
battery_voltage : (int16_t)(battery.voltage() * 100.0),
|
||||||
current_amps : (int16_t)(battery.current_amps() * 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()
|
current_total : battery.current_total_mah()
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
@ -535,15 +535,6 @@ static void check_usb_mux(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Read Vcc vs 1.1v internal reference
|
|
||||||
*/
|
|
||||||
uint16_t board_voltage(void)
|
|
||||||
{
|
|
||||||
return vcc_pin->voltage_latest() * 1000;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static void
|
static void
|
||||||
print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user