mirror of https://github.com/ArduPilot/ardupilot
Copter: sent battery voltage and current to motors
This commit is contained in:
parent
1217ab9579
commit
8eedb2c040
|
@ -150,6 +150,14 @@ static void read_battery(void)
|
||||||
compass.set_current(battery.current_amps());
|
compass.set_current(battery.current_amps());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// update motors with voltage and current
|
||||||
|
if (battery.get_type() != AP_BattMonitor::BattMonitor_TYPE_NONE) {
|
||||||
|
motors.set_voltage(battery.voltage());
|
||||||
|
}
|
||||||
|
if (battery.has_current()) {
|
||||||
|
motors.set_current(battery.current_amps());
|
||||||
|
}
|
||||||
|
|
||||||
// check for low voltage or current if the low voltage check hasn't already been triggered
|
// check for low voltage or current if the low voltage check hasn't already been triggered
|
||||||
// we only check when we're not powered by USB to avoid false alarms during bench tests
|
// we only check when we're not powered by USB to avoid false alarms during bench tests
|
||||||
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
||||||
|
|
Loading…
Reference in New Issue