Added Piezo Support, code from Oliver.
This commit is contained in:
parent
5bf7898438
commit
4425e72034
@ -182,7 +182,18 @@
|
||||
# define CURR_AMPS_OFFSET 0.0
|
||||
#endif
|
||||
#ifndef HIGH_DISCHARGE
|
||||
# define HIGH_DISCHARGE 1760
|
||||
# define HIGH_DISCHARGE 1760
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef PIEZO
|
||||
# define PIEZO ENABLED //Enables Piezo Code and beeps once on Startup to verify operation
|
||||
#endif
|
||||
#ifndef PIEZO_LOW_VOLTAGE
|
||||
# define PIEZO_LOW_VOLTAGE ENABLED //Enables Tone on reaching low battery or current alert
|
||||
#endif
|
||||
#ifndef PIEZO_ARMING
|
||||
# define PIEZO_ARMING ENABLED //Two tones on ARM, 1 Tone on disarm
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -95,3 +95,24 @@ static void relay_toggle()
|
||||
PORTL ^= B00000100;
|
||||
}
|
||||
|
||||
#if PIEZO == ENABLED
|
||||
void piezo_on()
|
||||
{
|
||||
digitalWrite(PIEZO_PIN,HIGH);
|
||||
//PORTF |= B00100000;
|
||||
}
|
||||
|
||||
void piezo_off()
|
||||
{
|
||||
digitalWrite(PIEZO_PIN,LOW);
|
||||
//PORTF &= ~B00100000;
|
||||
}
|
||||
|
||||
void piezo_beep()
|
||||
{
|
||||
// Note: This command should not be used in time sensitive loops
|
||||
piezo_on();
|
||||
delay(100);
|
||||
piezo_off();
|
||||
}
|
||||
#endif
|
||||
|
@ -31,6 +31,11 @@ static void arm_motors()
|
||||
motor_armed = true;
|
||||
arming_counter = ARM_DELAY;
|
||||
|
||||
#if PIEZO_ARMING == 1
|
||||
piezo_beep();
|
||||
piezo_beep();
|
||||
#endif
|
||||
|
||||
// Tune down DCM
|
||||
// -------------------
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
@ -92,6 +97,9 @@ static void arm_motors()
|
||||
arming_counter = DISARM_DELAY;
|
||||
compass.save_offsets();
|
||||
|
||||
#if PIEZO_ARMING == 1
|
||||
piezo_beep();
|
||||
#endif
|
||||
|
||||
// Tune down DCM
|
||||
// -------------------
|
||||
|
@ -126,11 +126,26 @@ static void read_battery(void)
|
||||
}
|
||||
|
||||
#if BATTERY_EVENT == 1
|
||||
if(battery_voltage < g.low_voltage)
|
||||
//if(battery_voltage < g.low_voltage)
|
||||
// low_battery_event();
|
||||
|
||||
if((battery_voltage < g.low_voltage) || (g.battery_monitoring == 4 && current_total > g.pack_capacity)){
|
||||
low_battery_event();
|
||||
|
||||
if(g.battery_monitoring == 4 && current_total > g.pack_capacity)
|
||||
low_battery_event();
|
||||
#if PIEZO_LOW_VOLTAGE == 1
|
||||
// Only Activate if a battery is connected to avoid alarm on USB only
|
||||
if (battery_voltage1 > 1){
|
||||
piezo_on();
|
||||
}else{
|
||||
piezo_off();
|
||||
}
|
||||
#endif
|
||||
|
||||
}else{
|
||||
#if PIEZO_LOW_VOLTAGE == 1
|
||||
piezo_off();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -103,6 +103,11 @@ static void init_ardupilot()
|
||||
pinMode(LE_LED, OUTPUT); // GPS status LED
|
||||
#endif
|
||||
|
||||
#if PIEZO == 1
|
||||
pinMode(PIEZO_PIN,OUTPUT);
|
||||
piezo_beep();
|
||||
#endif
|
||||
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
Loading…
Reference in New Issue
Block a user