mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 05:45:31 +03:00
new "beeper" CLI command
This commit is contained in:
parent
257865cff2
commit
b4fb558dd4
6 changed files with 199 additions and 85 deletions
|
@ -384,7 +384,6 @@ static void resetConf(void)
|
||||||
memset(&masterConfig, 0, sizeof(master_t));
|
memset(&masterConfig, 0, sizeof(master_t));
|
||||||
setProfile(0);
|
setProfile(0);
|
||||||
|
|
||||||
masterConfig.beeper_off.flags = BEEPER_OFF_FLAGS_MIN;
|
|
||||||
masterConfig.version = EEPROM_CONF_VERSION;
|
masterConfig.version = EEPROM_CONF_VERSION;
|
||||||
masterConfig.mixerMode = MIXER_QUADX;
|
masterConfig.mixerMode = MIXER_QUADX;
|
||||||
featureClearAll();
|
featureClearAll();
|
||||||
|
@ -1080,3 +1079,48 @@ uint32_t featureMask(void)
|
||||||
{
|
{
|
||||||
return masterConfig.enabledFeatures;
|
return masterConfig.enabledFeatures;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void beeperOffSet(uint32_t mask)
|
||||||
|
{
|
||||||
|
masterConfig.beeper_off_flags |= mask;
|
||||||
|
}
|
||||||
|
|
||||||
|
void beeperOffSetAll(void)
|
||||||
|
{
|
||||||
|
uint8_t beeperCount = beeperTableEntryCount() - 2;
|
||||||
|
uint32_t mask = 0;
|
||||||
|
for (int i = 0; i < beeperCount; i++){
|
||||||
|
mask |= (1 << i);
|
||||||
|
}
|
||||||
|
masterConfig.beeper_off_flags = mask;
|
||||||
|
}
|
||||||
|
|
||||||
|
void beeperOffClear(uint32_t mask)
|
||||||
|
{
|
||||||
|
masterConfig.beeper_off_flags &= ~(mask);
|
||||||
|
}
|
||||||
|
|
||||||
|
void beeperOffClearAll(void)
|
||||||
|
{
|
||||||
|
masterConfig.beeper_off_flags = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t getBeeperOffMask(void)
|
||||||
|
{
|
||||||
|
return masterConfig.beeper_off_flags;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setBeeperOffMask(uint32_t mask)
|
||||||
|
{
|
||||||
|
masterConfig.beeper_off_flags = mask;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t getPreferedBeeperOffMask(void)
|
||||||
|
{
|
||||||
|
return masterConfig.prefered_beeper_off_flags;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setPreferedBeeperOffMask(uint32_t mask)
|
||||||
|
{
|
||||||
|
masterConfig.prefered_beeper_off_flags = mask;
|
||||||
|
}
|
||||||
|
|
|
@ -54,6 +54,14 @@ void featureSet(uint32_t mask);
|
||||||
void featureClear(uint32_t mask);
|
void featureClear(uint32_t mask);
|
||||||
void featureClearAll(void);
|
void featureClearAll(void);
|
||||||
uint32_t featureMask(void);
|
uint32_t featureMask(void);
|
||||||
|
void beeperOffSet(uint32_t mask);
|
||||||
|
void beeperOffSetAll(void);
|
||||||
|
void beeperOffClear(uint32_t mask);
|
||||||
|
void beeperOffClearAll(void);
|
||||||
|
uint32_t getBeeperOffMask(void);
|
||||||
|
void setBeeperOffMask(uint32_t mask);
|
||||||
|
uint32_t getPreferedBeeperOffMask(void);
|
||||||
|
void setPreferedBeeperOffMask(uint32_t mask);
|
||||||
|
|
||||||
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
|
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex);
|
||||||
|
|
||||||
|
|
|
@ -139,6 +139,9 @@ typedef struct master_t {
|
||||||
uint8_t blackbox_device;
|
uint8_t blackbox_device;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
uint32_t beeper_off_flags;
|
||||||
|
uint32_t prefered_beeper_off_flags;
|
||||||
|
|
||||||
uint8_t magic_ef; // magic number, should be 0xEF
|
uint8_t magic_ef; // magic number, should be 0xEF
|
||||||
uint8_t chk; // XOR checksum
|
uint8_t chk; // XOR checksum
|
||||||
} master_t;
|
} master_t;
|
||||||
|
|
|
@ -15,63 +15,31 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include "stdbool.h"
|
||||||
#include "platform.h"
|
#include "stdint.h"
|
||||||
|
#include "stdlib.h"
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include <platform.h>
|
||||||
#include "common/axis.h"
|
#include "build_config.h"
|
||||||
#include "common/color.h"
|
|
||||||
#include "common/utils.h"
|
#include "io/rc_controls.h"
|
||||||
|
|
||||||
#include "drivers/gpio.h"
|
#include "drivers/gpio.h"
|
||||||
#include "drivers/sensor.h"
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/compass.h"
|
|
||||||
#include "drivers/timer.h"
|
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/accgyro.h"
|
|
||||||
#include "drivers/light_led.h"
|
|
||||||
#include "drivers/sound_beeper.h"
|
#include "drivers/sound_beeper.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
#include "sensors/sensors.h"
|
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "sensors/sonar.h"
|
|
||||||
#include "sensors/compass.h"
|
|
||||||
#include "sensors/acceleration.h"
|
|
||||||
#include "sensors/barometer.h"
|
|
||||||
#include "sensors/gyro.h"
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
#include "io/display.h"
|
|
||||||
#include "io/escservo.h"
|
|
||||||
#include "io/rc_controls.h"
|
|
||||||
#include "io/gimbal.h"
|
|
||||||
#include "io/gps.h"
|
|
||||||
#include "io/ledstrip.h"
|
|
||||||
#include "io/serial.h"
|
|
||||||
#include "io/serial_cli.h"
|
|
||||||
#include "io/serial_msp.h"
|
|
||||||
#include "io/statusindicator.h"
|
#include "io/statusindicator.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#ifdef GPS
|
||||||
#include "rx/msp.h"
|
#include "io/gps.h"
|
||||||
|
#endif
|
||||||
#include "telemetry/telemetry.h"
|
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
|
||||||
#include "flight/altitudehold.h"
|
|
||||||
#include "flight/failsafe.h"
|
|
||||||
#include "flight/imu.h"
|
|
||||||
#include "flight/navigation.h"
|
|
||||||
|
|
||||||
#include "io/beeper.h"
|
|
||||||
|
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "config/config_profile.h"
|
|
||||||
#include "config/config_master.h"
|
|
||||||
|
|
||||||
|
#include "io/beeper.h"
|
||||||
|
|
||||||
#if FLASH_SIZE > 64
|
#if FLASH_SIZE > 64
|
||||||
#define BEEPER_NAMES
|
#define BEEPER_NAMES
|
||||||
|
@ -82,6 +50,7 @@
|
||||||
#define BEEPER_COMMAND_REPEAT 0xFE
|
#define BEEPER_COMMAND_REPEAT 0xFE
|
||||||
#define BEEPER_COMMAND_STOP 0xFF
|
#define BEEPER_COMMAND_STOP 0xFF
|
||||||
|
|
||||||
|
#ifdef BEEPER
|
||||||
/* Beeper Sound Sequences: (Square wave generation)
|
/* Beeper Sound Sequences: (Square wave generation)
|
||||||
* Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
|
* Sequence must end with 0xFF or 0xFE. 0xFE repeats the sequence from
|
||||||
* start when 0xFF stops the sound when it's completed.
|
* start when 0xFF stops the sound when it's completed.
|
||||||
|
@ -182,23 +151,26 @@ typedef struct beeperTableEntry_s {
|
||||||
#define BEEPER_ENTRY(a,b,c,d) a,b,c
|
#define BEEPER_ENTRY(a,b,c,d) a,b,c
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static const beeperTableEntry_t beeperTable[] = {
|
/*static*/ const beeperTableEntry_t beeperTable[] = {
|
||||||
{ BEEPER_ENTRY(BEEPER_GYRO_CALIBRATED, 0, beep_gyroCalibrated, "GYRO_CALIBRATED") },
|
{ BEEPER_ENTRY(BEEPER_GYRO_CALIBRATED, 0, beep_gyroCalibrated, "GYRO_CALIBRATED") },
|
||||||
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 1, beep_sos, "RX_LOST_LANDING") },
|
{ BEEPER_ENTRY(BEEPER_RX_LOST, 1, beep_txLostBeep, "RX_LOST") },
|
||||||
{ BEEPER_ENTRY(BEEPER_RX_LOST, 2, beep_txLostBeep, "RX_LOST") },
|
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 2, beep_sos, "RX_LOST_LANDING") },
|
||||||
{ BEEPER_ENTRY(BEEPER_DISARMING, 3, beep_disarmBeep, "DISARMING") },
|
{ BEEPER_ENTRY(BEEPER_DISARMING, 3, beep_disarmBeep, "DISARMING") },
|
||||||
{ BEEPER_ENTRY(BEEPER_ARMING, 4, beep_armingBeep, "ARMING") },
|
{ BEEPER_ENTRY(BEEPER_ARMING, 4, beep_armingBeep, "ARMING") },
|
||||||
{ BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 5, beep_armedGpsFix, "ARMING_GPS_FIX") },
|
{ BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 5, beep_armedGpsFix, "ARMING_GPS_FIX") },
|
||||||
{ BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 6, beep_critBatteryBeep, "BAT_CRIT_LOW") },
|
{ BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 6, beep_critBatteryBeep, "BAT_CRIT_LOW") },
|
||||||
{ BEEPER_ENTRY(BEEPER_BAT_LOW, 7, beep_lowBatteryBeep, "BAT_LOW") },
|
{ BEEPER_ENTRY(BEEPER_BAT_LOW, 7, beep_lowBatteryBeep, "BAT_LOW") },
|
||||||
{ BEEPER_ENTRY(BEEPER_USB, 8, beep_multiBeeps, NULL) },
|
{ BEEPER_ENTRY(BEEPER_GPS_STATUS, 8, beep_multiBeeps, "GPS_STATUS") },
|
||||||
{ BEEPER_ENTRY(BEEPER_RX_SET, 9, beep_shortBeep, "RX_SET") },
|
{ BEEPER_ENTRY(BEEPER_RX_SET, 9, beep_shortBeep, "RX_SET") },
|
||||||
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION, 10, beep_2shortBeeps, "ACC_CALIBRATION") },
|
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION, 10, beep_2shortBeeps, "ACC_CALIBRATION") },
|
||||||
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION_FAIL, 11, beep_2longerBeeps, "ACC_CALIBRATION_FAIL") },
|
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION_FAIL, 11, beep_2longerBeeps, "ACC_CALIBRATION_FAIL") },
|
||||||
{ BEEPER_ENTRY(BEEPER_READY_BEEP, 12, beep_readyBeep, "READY_BEEP") },
|
{ BEEPER_ENTRY(BEEPER_READY_BEEP, 12, beep_readyBeep, "READY_BEEP") },
|
||||||
{ BEEPER_ENTRY(BEEPER_MULTI_BEEPS, 13, beep_multiBeeps, NULL) }, // FIXME having this listed makes no sense since the beep array will not be initialised.
|
{ BEEPER_ENTRY(BEEPER_MULTI_BEEPS, 13, beep_multiBeeps, "MULTI_BEEPS") }, // FIXME having this listed makes no sense since the beep array will not be initialised.
|
||||||
{ BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 14, beep_disarmRepeatBeep, "DISARM_REPEAT") },
|
{ BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 14, beep_disarmRepeatBeep, "DISARM_REPEAT") },
|
||||||
{ BEEPER_ENTRY(BEEPER_ARMED, 15, beep_armedBeep, "ARMED") },
|
{ BEEPER_ENTRY(BEEPER_ARMED, 15, beep_armedBeep, "ARMED") },
|
||||||
|
|
||||||
|
{ BEEPER_ENTRY(BEEPER_ALL, 16, NULL, "ALL") },
|
||||||
|
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 17, NULL, "PREFERED") },
|
||||||
};
|
};
|
||||||
|
|
||||||
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||||
|
@ -211,7 +183,7 @@ static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||||
*/
|
*/
|
||||||
void beeper(beeperMode_e mode)
|
void beeper(beeperMode_e mode)
|
||||||
{
|
{
|
||||||
if (mode == BEEPER_SILENCE || ((masterConfig.beeper_off.flags & (1 << (BEEPER_USB - 1))) && (feature(FEATURE_VBAT) && (batteryCellCount < 2)))) {
|
if (mode == BEEPER_SILENCE) {
|
||||||
beeperSilence();
|
beeperSilence();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -333,7 +305,7 @@ void beeperUpdate(void)
|
||||||
if (!beeperIsOn) {
|
if (!beeperIsOn) {
|
||||||
beeperIsOn = 1;
|
beeperIsOn = 1;
|
||||||
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
||||||
if (!(masterConfig.beeper_off.flags & (1 << (currentBeeperEntry->mode - 1))))
|
if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1))))
|
||||||
BEEP_ON;
|
BEEP_ON;
|
||||||
warningLedEnable();
|
warningLedEnable();
|
||||||
warningLedRefresh();
|
warningLedRefresh();
|
||||||
|
@ -407,7 +379,21 @@ const char *beeperNameForTableIndex(int idx)
|
||||||
/*
|
/*
|
||||||
* Returns the number of entries in the beeper-sounds table.
|
* Returns the number of entries in the beeper-sounds table.
|
||||||
*/
|
*/
|
||||||
int beeperTableEntryCount(void)
|
uint8_t beeperTableEntryCount(void)
|
||||||
{
|
{
|
||||||
return (int)BEEPER_TABLE_ENTRY_COUNT;
|
return (uint8_t)BEEPER_TABLE_ENTRY_COUNT;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
// Stub out beeper functions if #BEEPER not defined
|
||||||
|
void beeper(beeperMode_e mode) {UNUSED(mode);}
|
||||||
|
void beeperSilence(void) {}
|
||||||
|
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
|
||||||
|
void beeperUpdate(void) {}
|
||||||
|
uint32_t getArmingBeepTimeMicros(void) {return 0;}
|
||||||
|
beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;}
|
||||||
|
const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;}
|
||||||
|
uint8_t beeperTableEntryCount(void) {return 0;}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -22,14 +22,14 @@ typedef enum {
|
||||||
BEEPER_SILENCE = 0, // Silence, see beeperSilence()
|
BEEPER_SILENCE = 0, // Silence, see beeperSilence()
|
||||||
|
|
||||||
BEEPER_GYRO_CALIBRATED,
|
BEEPER_GYRO_CALIBRATED,
|
||||||
BEEPER_RX_LOST_LANDING, // Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
|
|
||||||
BEEPER_RX_LOST, // Beeps when TX is turned off or signal lost (repeat until TX is okay)
|
BEEPER_RX_LOST, // Beeps when TX is turned off or signal lost (repeat until TX is okay)
|
||||||
|
BEEPER_RX_LOST_LANDING, // Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
|
||||||
BEEPER_DISARMING, // Beep when disarming the board
|
BEEPER_DISARMING, // Beep when disarming the board
|
||||||
BEEPER_ARMING, // Beep when arming the board
|
BEEPER_ARMING, // Beep when arming the board
|
||||||
BEEPER_ARMING_GPS_FIX, // Beep a special tone when arming the board and GPS has fix
|
BEEPER_ARMING_GPS_FIX, // Beep a special tone when arming the board and GPS has fix
|
||||||
BEEPER_BAT_CRIT_LOW, // Longer warning beeps when battery is critically low (repeats)
|
BEEPER_BAT_CRIT_LOW, // Longer warning beeps when battery is critically low (repeats)
|
||||||
BEEPER_BAT_LOW, // Warning beeps when battery is getting low (repeats)
|
BEEPER_BAT_LOW, // Warning beeps when battery is getting low (repeats)
|
||||||
BEEPER_USB, // Disable beeper when connected to USB
|
BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB ****
|
||||||
BEEPER_RX_SET, // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled
|
BEEPER_RX_SET, // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled
|
||||||
BEEPER_DISARM_REPEAT, // Beeps sounded while stick held in disarm position
|
BEEPER_DISARM_REPEAT, // Beeps sounded while stick held in disarm position
|
||||||
BEEPER_ACC_CALIBRATION, // ACC inflight calibration completed confirmation
|
BEEPER_ACC_CALIBRATION, // ACC inflight calibration completed confirmation
|
||||||
|
@ -37,16 +37,12 @@ typedef enum {
|
||||||
BEEPER_READY_BEEP, // Ring a tone when GPS is locked and ready
|
BEEPER_READY_BEEP, // Ring a tone when GPS is locked and ready
|
||||||
BEEPER_MULTI_BEEPS, // Internal value used by 'beeperConfirmationBeeps()'.
|
BEEPER_MULTI_BEEPS, // Internal value used by 'beeperConfirmationBeeps()'.
|
||||||
BEEPER_ARMED, // Warning beeps when board is armed (repeats until board is disarmed or throttle is increased)
|
BEEPER_ARMED, // Warning beeps when board is armed (repeats until board is disarmed or throttle is increased)
|
||||||
BEEPER_CASE_MAX
|
|
||||||
|
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||||
|
BEEPER_PREFERENCE, // Save prefered beeper configuration
|
||||||
|
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
|
||||||
} beeperMode_e;
|
} beeperMode_e;
|
||||||
|
|
||||||
#define BEEPER_OFF_FLAGS_MIN 0
|
|
||||||
#define BEEPER_OFF_FLAGS_MAX ((1 << (BEEPER_CASE_MAX - 1)) - 1)
|
|
||||||
|
|
||||||
typedef struct beeperOffConditions_t {
|
|
||||||
uint32_t flags;
|
|
||||||
} beeperOffConditions_t;
|
|
||||||
|
|
||||||
void beeper(beeperMode_e mode);
|
void beeper(beeperMode_e mode);
|
||||||
void beeperSilence(void);
|
void beeperSilence(void);
|
||||||
void beeperUpdate(void);
|
void beeperUpdate(void);
|
||||||
|
@ -54,23 +50,4 @@ void beeperConfirmationBeeps(uint8_t beepCount);
|
||||||
uint32_t getArmingBeepTimeMicros(void);
|
uint32_t getArmingBeepTimeMicros(void);
|
||||||
beeperMode_e beeperModeForTableIndex(int idx);
|
beeperMode_e beeperModeForTableIndex(int idx);
|
||||||
const char *beeperNameForTableIndex(int idx);
|
const char *beeperNameForTableIndex(int idx);
|
||||||
int beeperTableEntryCount(void);
|
uint8_t beeperTableEntryCount(void);
|
||||||
|
|
||||||
/* CLI beeper_off_flags = sum of each desired beeper turned off case
|
|
||||||
BEEPER_GYRO_CALIBRATED, 1
|
|
||||||
BEEPER_RX_LOST_LANDING, 2 // Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
|
|
||||||
BEEPER_RX_LOST, 4 // Beeps when TX is turned off or signal lost (repeat until TX is okay)
|
|
||||||
BEEPER_DISARMING, 8 // Beep when disarming the board
|
|
||||||
BEEPER_ARMING, 16 // Beep when arming the board
|
|
||||||
BEEPER_ARMING_GPS_FIX, 32 // Beep a special tone when arming the board and GPS has fix
|
|
||||||
BEEPER_BAT_CRIT_LOW, 64 // Longer warning beeps when battery is critically low (repeats)
|
|
||||||
BEEPER_BAT_LOW, 128 // Warning beeps when battery is getting low (repeats)
|
|
||||||
BEEPER_USB_DISABLE, 256 // Disable beeper when connected to USB
|
|
||||||
BEEPER_RX_SET, 512 // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled
|
|
||||||
BEEPER_DISARM_REPEAT, 1024 // Beeps sounded while stick held in disarm position
|
|
||||||
BEEPER_ACC_CALIBRATION, 2048 // ACC inflight calibration completed confirmation
|
|
||||||
BEEPER_ACC_CALIBRATION_FAIL, 4096 // ACC inflight calibration failed
|
|
||||||
BEEPER_READY_BEEP, 8192 // Ring a tone when GPS is locked and ready
|
|
||||||
BEEPER_MULTI_BEEPS, 16384 // Internal value used by 'beeperConfirmationBeeps()'.
|
|
||||||
BEEPER_ARMED, 32768 // Warning beeps when board is armed (repeats until board is disarmed or throttle is increased)
|
|
||||||
*/
|
|
||||||
|
|
|
@ -165,6 +165,10 @@ static void cliFlashRead(char *cmdline);
|
||||||
static void cliSdInfo(char *cmdline);
|
static void cliSdInfo(char *cmdline);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef BEEPER
|
||||||
|
static void cliBeeper(char *cmdline);
|
||||||
|
#endif
|
||||||
|
|
||||||
// buffer
|
// buffer
|
||||||
static char cliBuffer[48];
|
static char cliBuffer[48];
|
||||||
static uint32_t bufferIndex = 0;
|
static uint32_t bufferIndex = 0;
|
||||||
|
@ -314,6 +318,10 @@ const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
|
CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
|
||||||
#endif
|
#endif
|
||||||
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
|
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
|
||||||
|
#ifdef BEEPER
|
||||||
|
CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
|
||||||
|
"\t<+|->[name]", cliBeeper),
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
#define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
|
#define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
|
||||||
|
|
||||||
|
@ -1885,6 +1893,21 @@ static void cliDump(char *cmdline)
|
||||||
cliPrintf("feature %s\r\n", featureNames[i]);
|
cliPrintf("feature %s\r\n", featureNames[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef BEEPER
|
||||||
|
cliPrint("\r\n\r\n# beeper\r\n");
|
||||||
|
|
||||||
|
uint8_t beeperCount = beeperTableEntryCount();
|
||||||
|
mask = getBeeperOffMask();
|
||||||
|
for (int i = 0; i < (beeperCount-2); i++) {
|
||||||
|
if (mask & (1 << i))
|
||||||
|
cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
|
||||||
|
else
|
||||||
|
cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
cliPrint("\r\n\r\n# map\r\n");
|
cliPrint("\r\n\r\n# map\r\n");
|
||||||
|
|
||||||
for (i = 0; i < 8; i++)
|
for (i = 0; i < 8; i++)
|
||||||
|
@ -2070,6 +2093,79 @@ static void cliFeature(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef BEEPER
|
||||||
|
static void cliBeeper(char *cmdline)
|
||||||
|
{
|
||||||
|
uint32_t i;
|
||||||
|
uint32_t len = strlen(cmdline);;
|
||||||
|
uint8_t beeperCount = beeperTableEntryCount();
|
||||||
|
uint32_t mask = getBeeperOffMask();
|
||||||
|
|
||||||
|
if (len == 0) {
|
||||||
|
cliPrintf("Disabled:");
|
||||||
|
for (int i = 0; ; i++) {
|
||||||
|
if (i == beeperCount-2){
|
||||||
|
if (mask == 0)
|
||||||
|
cliPrint(" none");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (mask & (1 << i))
|
||||||
|
cliPrintf(" %s", beeperNameForTableIndex(i));
|
||||||
|
}
|
||||||
|
cliPrint("\r\n");
|
||||||
|
} else if (strncasecmp(cmdline, "list", len) == 0) {
|
||||||
|
cliPrint("Available:");
|
||||||
|
for (i = 0; i < beeperCount; i++)
|
||||||
|
cliPrintf(" %s", beeperNameForTableIndex(i));
|
||||||
|
cliPrint("\r\n");
|
||||||
|
return;
|
||||||
|
} else {
|
||||||
|
bool remove = false;
|
||||||
|
if (cmdline[0] == '-') {
|
||||||
|
remove = true; // this is for beeper OFF condition
|
||||||
|
cmdline++;
|
||||||
|
len--;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (i = 0; ; i++) {
|
||||||
|
if (i == beeperCount) {
|
||||||
|
cliPrint("Invalid name\r\n");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
|
||||||
|
if (remove) { // beeper off
|
||||||
|
if (i == BEEPER_ALL-1)
|
||||||
|
beeperOffSetAll();
|
||||||
|
else
|
||||||
|
if (i == BEEPER_PREFERENCE-1)
|
||||||
|
setBeeperOffMask(getPreferedBeeperOffMask());
|
||||||
|
else {
|
||||||
|
mask = 1 << i;
|
||||||
|
beeperOffSet(mask);
|
||||||
|
}
|
||||||
|
cliPrint("Disabled");
|
||||||
|
}
|
||||||
|
else { // beeper on
|
||||||
|
if (i == BEEPER_ALL-1)
|
||||||
|
beeperOffClearAll();
|
||||||
|
else
|
||||||
|
if (i == BEEPER_PREFERENCE-1)
|
||||||
|
setPreferedBeeperOffMask(getBeeperOffMask());
|
||||||
|
else {
|
||||||
|
mask = 1 << i;
|
||||||
|
beeperOffClear(mask);
|
||||||
|
}
|
||||||
|
cliPrint("Enabled");
|
||||||
|
}
|
||||||
|
cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
static void cliGpsPassthrough(char *cmdline)
|
static void cliGpsPassthrough(char *cmdline)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue