mirror of https://github.com/ArduPilot/ardupilot
Rover: CUR and CURR renamed to CURRENT in dataflash
Based on user complaint re inconsistency of disabling/enabling and output in dataflash
This commit is contained in:
parent
648caff1c6
commit
bb21194fd7
|
@ -894,7 +894,7 @@ static void slow_loop()
|
|||
static void one_second_loop()
|
||||
{
|
||||
#if LITE == DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_CUR)
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT)
|
||||
Log_Write_Current();
|
||||
#endif
|
||||
// send a heartbeat
|
||||
|
|
|
@ -57,7 +57,7 @@ print_log_menu(void)
|
|||
PLOG(MODE);
|
||||
PLOG(IMU);
|
||||
PLOG(CMD);
|
||||
PLOG(CUR);
|
||||
PLOG(CURRENT);
|
||||
#undef PLOG
|
||||
}
|
||||
|
||||
|
@ -178,7 +178,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
TARG(MODE);
|
||||
TARG(IMU);
|
||||
TARG(CMD);
|
||||
TARG(CUR);
|
||||
TARG(CURRENT);
|
||||
#undef TARG
|
||||
}
|
||||
|
||||
|
@ -370,7 +370,7 @@ static void Log_Write_Current()
|
|||
// Read a Current packet
|
||||
static void Log_Read_Current()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("CURR, %d, %4.4f, %4.4f, %d\n"),
|
||||
cliSerial->printf_P(PSTR("CURRENT, %d, %4.4f, %4.4f, %d\n"),
|
||||
DataFlash.ReadInt(),
|
||||
((float)DataFlash.ReadInt() / 100.f),
|
||||
((float)DataFlash.ReadInt() / 100.f),
|
||||
|
|
|
@ -661,8 +661,8 @@
|
|||
#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
|
||||
|
@ -678,7 +678,7 @@
|
|||
LOGBIT(MODE) | \
|
||||
LOGBIT(IMU) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CUR)
|
||||
LOGBIT(CURRENT)
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -157,7 +157,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)
|
||||
|
||||
// Waypoint Modes
|
||||
// ----------------
|
||||
|
|
Loading…
Reference in New Issue