mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: rename CUR and CURR to CURRENT for logging
Based on user complaint that log was enabled/disabled using CUR while message that appeared in log was CURR.
This commit is contained in:
parent
6f46f4a7d0
commit
e674626fd6
@ -961,7 +961,7 @@ static void slow_loop()
|
||||
|
||||
static void one_second_loop()
|
||||
{
|
||||
if (g.log_bitmask & MASK_LOG_CUR)
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT)
|
||||
Log_Write_Current();
|
||||
|
||||
// send a heartbeat
|
||||
|
@ -54,7 +54,7 @@ print_log_menu(void)
|
||||
PLOG(MODE);
|
||||
PLOG(RAW);
|
||||
PLOG(CMD);
|
||||
PLOG(CUR);
|
||||
PLOG(CURRENT);
|
||||
#undef PLOG
|
||||
}
|
||||
|
||||
@ -170,7 +170,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
||||
TARG(MODE);
|
||||
TARG(RAW);
|
||||
TARG(CMD);
|
||||
TARG(CUR);
|
||||
TARG(CURRENT);
|
||||
#undef TARG
|
||||
}
|
||||
|
||||
@ -598,7 +598,7 @@ static void Log_Read_Current()
|
||||
{
|
||||
struct log_Current pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("CURR, %d, %4.4f, %4.4f, %d\n"),
|
||||
cliSerial->printf_P(PSTR("CURRENT, %d, %4.4f, %4.4f, %d\n"),
|
||||
(int)pkt.throttle_in,
|
||||
((float)pkt.battery_voltage / 100.f),
|
||||
((float)pkt.current_amps / 100.f),
|
||||
|
@ -739,24 +739,24 @@
|
||||
#ifndef LOG_CMD
|
||||
# define LOG_CMD ENABLED
|
||||
#endif
|
||||
#ifndef LOG_CUR
|
||||
# define LOG_CUR DISABLED
|
||||
#ifndef LOG_CURRENT
|
||||
# define LOG_CURRENT DISABLED
|
||||
#endif
|
||||
|
||||
// calculate the default log_bitmask
|
||||
#define LOGBIT(_s) (LOG_ ## _s ? MASK_LOG_ ## _s : 0)
|
||||
|
||||
#define DEFAULT_LOG_BITMASK \
|
||||
LOGBIT(ATTITUDE_FAST) | \
|
||||
LOGBIT(ATTITUDE_MED) | \
|
||||
LOGBIT(GPS) | \
|
||||
LOGBIT(PM) | \
|
||||
LOGBIT(CTUN) | \
|
||||
LOGBIT(NTUN) | \
|
||||
LOGBIT(MODE) | \
|
||||
LOGBIT(RAW) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CUR)
|
||||
#define DEFAULT_LOG_BITMASK \
|
||||
LOGBIT(ATTITUDE_FAST) | \
|
||||
LOGBIT(ATTITUDE_MED) | \
|
||||
LOGBIT(GPS) | \
|
||||
LOGBIT(PM) | \
|
||||
LOGBIT(CTUN) | \
|
||||
LOGBIT(NTUN) | \
|
||||
LOGBIT(MODE) | \
|
||||
LOGBIT(RAW) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CURRENT)
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -163,7 +163,7 @@ enum log_messages {
|
||||
#define MASK_LOG_MODE (1<<6)
|
||||
#define MASK_LOG_RAW (1<<7)
|
||||
#define MASK_LOG_CMD (1<<8)
|
||||
#define MASK_LOG_CUR (1<<9)
|
||||
#define MASK_LOG_CURRENT (1<<9)
|
||||
|
||||
// Waypoint Modes
|
||||
// ----------------
|
||||
|
Loading…
Reference in New Issue
Block a user