mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: rename CUR and CURR to CURRENT for logging
Based on user complaint that enable/disable was using CUR while message was appearing as CURR
This commit is contained in:
parent
e674626fd6
commit
ce370bab0c
@ -1345,7 +1345,7 @@ static void super_slow_loop()
|
||||
Log_Write_Data(DATA_AP_STATE, ap.value);
|
||||
}
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_CUR && motors.armed())
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT && motors.armed())
|
||||
Log_Write_Current();
|
||||
|
||||
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 25 seconds
|
||||
|
@ -49,7 +49,7 @@ print_log_menu(void)
|
||||
if (g.log_bitmask & MASK_LOG_NTUN) cliSerial->printf_P(PSTR(" NTUN"));
|
||||
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(PSTR(" IMU"));
|
||||
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf_P(PSTR(" CMD"));
|
||||
if (g.log_bitmask & MASK_LOG_CUR) cliSerial->printf_P(PSTR(" CURRENT"));
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf_P(PSTR(" CURRENT"));
|
||||
if (g.log_bitmask & MASK_LOG_MOTORS) cliSerial->printf_P(PSTR(" MOTORS"));
|
||||
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
|
||||
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(PSTR(" PID"));
|
||||
@ -167,7 +167,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
||||
TARG(MODE);
|
||||
TARG(IMU);
|
||||
TARG(CMD);
|
||||
TARG(CUR);
|
||||
TARG(CURRENT);
|
||||
TARG(MOTORS);
|
||||
TARG(OPTFLOW);
|
||||
TARG(PID);
|
||||
@ -325,8 +325,8 @@ static void Log_Read_Current()
|
||||
struct log_Current pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
|
||||
// 1 2 3 4 5
|
||||
cliSerial->printf_P(PSTR("CURR, %d, %lu, %4.4f, %4.4f, %d\n"),
|
||||
// 1 2 3 4 5
|
||||
cliSerial->printf_P(PSTR("CURRENT, %d, %lu, %4.4f, %4.4f, %d\n"),
|
||||
(int)pkt.throttle_in,
|
||||
(unsigned long)pkt.throttle_integrator,
|
||||
(float)pkt.battery_voltage/100.0f,
|
||||
|
@ -1133,8 +1133,8 @@
|
||||
# define LOG_CMD ENABLED
|
||||
#endif
|
||||
// current
|
||||
#ifndef LOG_CUR
|
||||
# define LOG_CUR DISABLED
|
||||
#ifndef LOG_CURRENT
|
||||
# define LOG_CURRENT DISABLED
|
||||
#endif
|
||||
// quad motor PWMs
|
||||
#ifndef LOG_MOTORS
|
||||
@ -1170,7 +1170,7 @@
|
||||
LOGBIT(MODE) | \
|
||||
LOGBIT(IMU) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CUR) | \
|
||||
LOGBIT(CURRENT) | \
|
||||
LOGBIT(MOTORS) | \
|
||||
LOGBIT(OPTFLOW) | \
|
||||
LOGBIT(PID) | \
|
||||
|
@ -308,7 +308,7 @@ enum gcs_severity {
|
||||
#define MASK_LOG_MODE (1<<6)
|
||||
#define MASK_LOG_IMU (1<<7)
|
||||
#define MASK_LOG_CMD (1<<8)
|
||||
#define MASK_LOG_CUR (1<<9)
|
||||
#define MASK_LOG_CURRENT (1<<9)
|
||||
#define MASK_LOG_MOTORS (1<<10)
|
||||
#define MASK_LOG_OPTFLOW (1<<11)
|
||||
#define MASK_LOG_PID (1<<12)
|
||||
|
Loading…
Reference in New Issue
Block a user