Browse Source

Copter: pre-arm check for board voltage < 5.8V

mission-4.1.18
Randy Mackay 12 years ago
parent
commit
a1821c89e7
  1. 4
      ArduCopter/config.h
  2. 4
      ArduCopter/motors.pde

4
ArduCopter/config.h

@ -386,6 +386,10 @@
# define BOARD_VOLTAGE_MIN 4500 // min board voltage in milli volts for pre-arm checks # define BOARD_VOLTAGE_MIN 4500 // min board voltage in milli volts for pre-arm checks
#endif #endif
#ifndef BOARD_VOLTAGE_MAX
# define BOARD_VOLTAGE_MAX 5800 // max board voltage in milli volts for pre-arm checks
#endif
// Battery failsafe // Battery failsafe
#ifndef FS_BATTERY #ifndef FS_BATTERY
# define FS_BATTERY DISABLED # define FS_BATTERY DISABLED

4
ArduCopter/motors.pde

@ -266,9 +266,9 @@ static void pre_arm_checks(bool display_failure)
#if CONFIG_HAL_BOARD != HAL_BOARD_PX4 #if CONFIG_HAL_BOARD != HAL_BOARD_PX4
// check board voltage // check board voltage
if(board_voltage() < BOARD_VOLTAGE_MIN) { if(board_voltage() < BOARD_VOLTAGE_MIN || board_voltage() > BOARD_VOLTAGE_MAX) {
if (display_failure) { if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Low Board Voltage")); gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check Board Voltage"));
} }
return; return;
} }

Loading…
Cancel
Save