mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 16:53:57 -04:00
ArduCopter: low baterry failsafe
This commit is contained in:
parent
414f9b9759
commit
3a4d122e32
@ -174,6 +174,7 @@ public:
|
|||||||
k_param_radio_tuning_high,
|
k_param_radio_tuning_high,
|
||||||
k_param_radio_tuning_low,
|
k_param_radio_tuning_low,
|
||||||
k_param_rc_speed = 192,
|
k_param_rc_speed = 192,
|
||||||
|
k_param_battery_fs_enabled, // 193
|
||||||
|
|
||||||
//
|
//
|
||||||
// 200: flight modes
|
// 200: flight modes
|
||||||
@ -246,8 +247,9 @@ public:
|
|||||||
AP_Float volt_div_ratio;
|
AP_Float volt_div_ratio;
|
||||||
AP_Float curr_amp_per_volt;
|
AP_Float curr_amp_per_volt;
|
||||||
AP_Float input_voltage;
|
AP_Float input_voltage;
|
||||||
AP_Int16 pack_capacity; // Battery pack capacity less
|
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
||||||
// reserve
|
AP_Int8 battery_fs_enabled; // battery failsafe enabled
|
||||||
|
|
||||||
AP_Int8 compass_enabled;
|
AP_Int8 compass_enabled;
|
||||||
AP_Int8 optflow_enabled;
|
AP_Int8 optflow_enabled;
|
||||||
AP_Float low_voltage;
|
AP_Float low_voltage;
|
||||||
|
@ -53,8 +53,16 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GSCALAR(sonar_enabled, "SONAR_ENABLE", DISABLED),
|
GSCALAR(sonar_enabled, "SONAR_ENABLE", DISABLED),
|
||||||
|
|
||||||
GSCALAR(sonar_type, "SONAR_TYPE", AP_RANGEFINDER_MAXSONARXL),
|
GSCALAR(sonar_type, "SONAR_TYPE", AP_RANGEFINDER_MAXSONARXL),
|
||||||
|
|
||||||
GSCALAR(battery_monitoring, "BATT_MONITOR", DISABLED),
|
GSCALAR(battery_monitoring, "BATT_MONITOR", DISABLED),
|
||||||
|
|
||||||
|
// @Param: BATT_FAILSAFE
|
||||||
|
// @DisplayName: Battery Failsafe Enable
|
||||||
|
// @Description: Controls whether failsafe will be invoked when battery voltage or current runs low
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
// @User: Standard
|
||||||
|
GSCALAR(battery_fs_enabled, "BATT_FAILSAFE", BATTERY_FAILSAFE),
|
||||||
|
|
||||||
// @Param: VOLT_DIVIDER
|
// @Param: VOLT_DIVIDER
|
||||||
// @DisplayName: Voltage Divider
|
// @DisplayName: Voltage Divider
|
||||||
// @Description: TODO
|
// @Description: TODO
|
||||||
|
@ -303,9 +303,6 @@
|
|||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Battery monitoring
|
// Battery monitoring
|
||||||
//
|
//
|
||||||
#ifndef BATTERY_EVENT
|
|
||||||
# define BATTERY_EVENT DISABLED
|
|
||||||
#endif
|
|
||||||
#ifndef LOW_VOLTAGE
|
#ifndef LOW_VOLTAGE
|
||||||
# define LOW_VOLTAGE 9.6
|
# define LOW_VOLTAGE 9.6
|
||||||
#endif
|
#endif
|
||||||
@ -323,7 +320,10 @@
|
|||||||
# define HIGH_DISCHARGE 1760
|
# define HIGH_DISCHARGE 1760
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Battery failsafe
|
||||||
|
#ifndef BATTERY_FAILSAFE
|
||||||
|
# define BATTERY_FAILSAFE DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -6,6 +6,11 @@
|
|||||||
*/
|
*/
|
||||||
static void failsafe_on_event()
|
static void failsafe_on_event()
|
||||||
{
|
{
|
||||||
|
// if motors are not armed there is nothing to do
|
||||||
|
if( !motors.armed() ) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// This is how to handle a failsafe.
|
// This is how to handle a failsafe.
|
||||||
switch(control_mode) {
|
switch(control_mode) {
|
||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
@ -27,6 +32,7 @@ static void failsafe_on_event()
|
|||||||
case AUTO:
|
case AUTO:
|
||||||
// throttle_fs_action is 1 do RTL, everything else means continue with the mission
|
// throttle_fs_action is 1 do RTL, everything else means continue with the mission
|
||||||
if (g.throttle_fs_action == THROTTLE_FAILSAFE_ACTION_ALWAYS_RTL) {
|
if (g.throttle_fs_action == THROTTLE_FAILSAFE_ACTION_ALWAYS_RTL) {
|
||||||
|
// To-Do: check distance from home before initiating RTL
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}
|
}
|
||||||
// if throttle_fs_action is 2 (i.e. THROTTLE_FAILSAFE_ACTION_CONTINUE_MISSION) no need to do anything
|
// if throttle_fs_action is 2 (i.e. THROTTLE_FAILSAFE_ACTION_CONTINUE_MISSION) no need to do anything
|
||||||
@ -35,6 +41,7 @@ static void failsafe_on_event()
|
|||||||
if(ap.home_is_set == true) {
|
if(ap.home_is_set == true) {
|
||||||
// same as above ^
|
// same as above ^
|
||||||
// do_rtl sets the altitude to the current altitude by default
|
// do_rtl sets the altitude to the current altitude by default
|
||||||
|
// To-Do: check distance from home before initiating RTL
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}else{
|
}else{
|
||||||
// We have no GPS so we will crash land in alt hold mode
|
// We have no GPS so we will crash land in alt hold mode
|
||||||
@ -58,19 +65,39 @@ static void failsafe_off_event()
|
|||||||
|
|
||||||
static void low_battery_event(void)
|
static void low_battery_event(void)
|
||||||
{
|
{
|
||||||
static uint32_t last_low_battery_message;
|
// warn the ground station
|
||||||
uint32_t tnow = millis();
|
gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!"));
|
||||||
if (((uint32_t)(tnow - last_low_battery_message)) > 5000) {
|
|
||||||
// only send this message at 5s intervals at most or we may
|
// failsafe check
|
||||||
// flood the link
|
if (g.battery_fs_enabled && !ap.low_battery && motors.armed()) {
|
||||||
gcs_send_text_P(SEVERITY_LOW,PSTR("Low Battery!"));
|
switch(control_mode) {
|
||||||
last_low_battery_message = tnow;
|
case STABILIZE:
|
||||||
|
case ACRO:
|
||||||
|
// if throttle is zero disarm motors
|
||||||
|
if (g.rc_3.control_in == 0) {
|
||||||
|
init_disarm_motors();
|
||||||
|
}else{
|
||||||
|
set_mode(LAND);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case AUTO:
|
||||||
|
// To-Do: check distance to home before initiating RTL?
|
||||||
|
set_mode(RTL);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
set_mode(LAND);
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// set the low battery flag
|
||||||
set_low_battery(true);
|
set_low_battery(true);
|
||||||
// if we are in Auto mode, come home
|
|
||||||
if(control_mode >= AUTO)
|
#if COPTER_LEDS == ENABLED
|
||||||
set_mode(RTL);
|
if ( bitRead(g.copter_leds_mode, 3) ) { // Only Activate if a battery is connected to avoid alarm on USB only
|
||||||
|
piezo_on();
|
||||||
|
}
|
||||||
|
#endif // COPTER_LEDS
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -68,8 +68,12 @@ static void init_optflow()
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// read_battery - check battery voltage and current and invoke failsafe if necessary
|
||||||
|
// called at 10hz
|
||||||
|
#define BATTERY_FS_COUNTER 100 // 100 iterations at 10hz is 10 seconds
|
||||||
static void read_battery(void)
|
static void read_battery(void)
|
||||||
{
|
{
|
||||||
|
static uint8_t low_battery_counter = 0;
|
||||||
|
|
||||||
if(g.battery_monitoring == 0) {
|
if(g.battery_monitoring == 0) {
|
||||||
battery_voltage1 = 0;
|
battery_voltage1 = 0;
|
||||||
@ -88,28 +92,15 @@ static void read_battery(void)
|
|||||||
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
||||||
}
|
}
|
||||||
|
|
||||||
#if BATTERY_EVENT == ENABLED
|
// check for low voltage or current if the low voltage check hasn't already been triggered
|
||||||
//if(battery_voltage < g.low_voltage)
|
if (!ap.low_battery && ( battery_voltage1 < g.low_voltage || (g.battery_monitoring == 4 && current_total1 > g.pack_capacity))) {
|
||||||
// low_battery_event();
|
low_battery_counter++;
|
||||||
|
if( low_battery_counter >= BATTERY_FS_COUNTER ) {
|
||||||
if((battery_voltage1 < g.low_voltage) || (g.battery_monitoring == 4 && current_total1 > g.pack_capacity)) {
|
low_battery_counter = BATTERY_FS_COUNTER; // ensure counter does not overflow
|
||||||
low_battery_event();
|
low_battery_event();
|
||||||
|
|
||||||
#if COPTER_LEDS == ENABLED
|
|
||||||
if ( bitRead(g.copter_leds_mode, 3) ) { // Only Activate if a battery is connected to avoid alarm on USB only
|
|
||||||
if (battery_voltage1 > 1) {
|
|
||||||
piezo_on();
|
|
||||||
}else{
|
|
||||||
piezo_off();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
}else{
|
||||||
|
// reset low_battery_counter in case it was a temporary voltage dip
|
||||||
}else if ( bitRead(g.copter_leds_mode, 3) ) {
|
low_battery_counter = 0;
|
||||||
piezo_off();
|
|
||||||
#endif // COPTER_LEDS
|
|
||||||
}
|
}
|
||||||
#endif //BATTERY_EVENT
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//v: 10.9453, a: 17.4023, mah: 8.2
|
|
||||||
|
Loading…
Reference in New Issue
Block a user