mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Refactor
Changed mask var from 16 to 32 bits Changed variables names Inverse logic Added definitions to cli settings Added logging_fields_mask to blackbox header
This commit is contained in:
parent
6d9e4a813a
commit
d21b1fa77a
5 changed files with 67 additions and 59 deletions
|
@ -778,18 +778,26 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef USE_BLACKBOX
|
||||
{ "blackbox_sample_rate", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_SAMPLE_RATE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, sample_rate) },
|
||||
{ "blackbox_device", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
|
||||
{ "bb_log_pids", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_PID, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_rc", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_RC_COMMANDS, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_setpoint", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_SETPOINT, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_bat", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_BATTERY, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_mag", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_MAG, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_alt", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_ALTITUDE, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_rssi", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_RSSI, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_gyro", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_GYRO, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_acc", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_ACC, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_debug", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_DEBUG, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_motors", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_MOTOR, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "bb_log_gps", VAR_UINT16 | MASTER_VALUE | MODE_BITSET, .config.bitpos = SELECT_FIELD_GPS, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields) },
|
||||
{ "blackbox_disable_pids", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_PID, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
{ "blackbox_disable_rc", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_RC_COMMANDS, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
{ "blackbox_disable_setpoint", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_SETPOINT, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
{ "blackbox_disable_bat", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_BATTERY, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#ifdef USE_MAG
|
||||
{ "blackbox_disable_mag", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_MAG, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#endif
|
||||
#if defined(USE_BARO) || defined(USE_RANGEFINDER)
|
||||
{ "blackbox_disable_alt", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_ALTITUDE, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#endif
|
||||
{ "blackbox_disable_rssi", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_RSSI, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
{ "blackbox_disable_gyro", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_GYRO, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#if defined(USE_ACC)
|
||||
{ "blackbox_disable_acc", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_ACC, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#endif
|
||||
{ "blackbox_disable_debug", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_DEBUG, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
{ "blackbox_disable_motors", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_MOTOR, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#ifdef USE_GPS
|
||||
{ "blackbox_disable_gps", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = FLIGHT_LOG_FIELD_SELECT_GPS, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, fields_mask) },
|
||||
#endif
|
||||
{ "blackbox_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_MODE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, mode) },
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue