mirror of https://github.com/ArduPilot/ardupilot
Rover: rename RAW dataflash message to IMU
This commit is contained in:
parent
7297a1ff83
commit
7bfe659626
|
@ -707,8 +707,8 @@ static void fast_loop()
|
|||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
|
||||
Log_Write_Attitude((int)ahrs.roll_sensor, (int)ahrs.pitch_sensor, (uint16_t)ahrs.yaw_sensor);
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_RAW)
|
||||
Log_Write_Raw();
|
||||
if (g.log_bitmask & MASK_LOG_IMU)
|
||||
Log_Write_IMU();
|
||||
#endif
|
||||
#endif
|
||||
// inertial navigation
|
||||
|
|
|
@ -55,7 +55,7 @@ print_log_menu(void)
|
|||
PLOG(CTUN);
|
||||
PLOG(NTUN);
|
||||
PLOG(MODE);
|
||||
PLOG(RAW);
|
||||
PLOG(IMU);
|
||||
PLOG(CMD);
|
||||
PLOG(CUR);
|
||||
#undef PLOG
|
||||
|
@ -176,7 +176,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
TARG(CTUN);
|
||||
TARG(NTUN);
|
||||
TARG(MODE);
|
||||
TARG(RAW);
|
||||
TARG(IMU);
|
||||
TARG(CMD);
|
||||
TARG(CUR);
|
||||
#undef TARG
|
||||
|
@ -337,7 +337,7 @@ static void Log_Write_GPS( int32_t log_Time, int32_t log_Lattitude, int32_t log_
|
|||
|
||||
// Write an raw accel/gyro data packet. Total length : 28 bytes
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
static void Log_Write_Raw()
|
||||
static void Log_Write_IMU()
|
||||
{
|
||||
Vector3f gyro = ins.get_gyro();
|
||||
Vector3f accel = ins.get_accel();
|
||||
|
@ -345,7 +345,7 @@ static void Log_Write_Raw()
|
|||
accel *= t7;
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_RAW_MSG);
|
||||
DataFlash.WriteByte(LOG_IMU_MSG);
|
||||
|
||||
DataFlash.WriteLong((long)gyro.x);
|
||||
DataFlash.WriteLong((long)gyro.y);
|
||||
|
@ -526,10 +526,10 @@ static void Log_Read_GPS()
|
|||
}
|
||||
|
||||
// Read a raw accel/gyro packet
|
||||
static void Log_Read_Raw()
|
||||
static void Log_Read_IMU()
|
||||
{
|
||||
float logvar;
|
||||
cliSerial->printf_P(PSTR("RAW: "));
|
||||
cliSerial->printf_P(PSTR("IMU: "));
|
||||
for (int y = 0; y < 6; y++) {
|
||||
logvar = (float)DataFlash.ReadLong() / t7;
|
||||
cliSerial->print(logvar);
|
||||
|
@ -573,8 +573,8 @@ static void log_callback(uint8_t msgid)
|
|||
Log_Read_Performance();
|
||||
break;
|
||||
|
||||
case LOG_RAW_MSG:
|
||||
Log_Read_Raw();
|
||||
case LOG_IMU_MSG:
|
||||
Log_Read_IMU();
|
||||
break;
|
||||
|
||||
case LOG_CMD_MSG:
|
||||
|
@ -609,7 +609,7 @@ static void Log_Write_Performance() {}
|
|||
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
|
||||
static void Log_Write_Attitude(int16_t log_roll, int16_t log_pitch, uint16_t log_yaw) {}
|
||||
static void Log_Write_Control_Tuning() {}
|
||||
static void Log_Write_Raw() {}
|
||||
static void Log_Write_IMU() {}
|
||||
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
|
|
|
@ -655,8 +655,8 @@
|
|||
#ifndef LOG_MODE
|
||||
# define LOG_MODE ENABLED
|
||||
#endif
|
||||
#ifndef LOG_RAW
|
||||
# define LOG_RAW DISABLED
|
||||
#ifndef LOG_IMU
|
||||
# define LOG_IMU DISABLED
|
||||
#endif
|
||||
#ifndef LOG_CMD
|
||||
# define LOG_CMD ENABLED
|
||||
|
@ -676,7 +676,7 @@
|
|||
LOGBIT(CTUN) | \
|
||||
LOGBIT(NTUN) | \
|
||||
LOGBIT(MODE) | \
|
||||
LOGBIT(RAW) | \
|
||||
LOGBIT(IMU) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CUR)
|
||||
|
||||
|
|
|
@ -135,27 +135,27 @@ enum gcs_severity {
|
|||
// Logging parameters
|
||||
#define LOG_INDEX_MSG 0xF0
|
||||
#define LOG_ATTITUDE_MSG 0x01
|
||||
#define LOG_GPS_MSG 0x02
|
||||
#define LOG_GPS_MSG 0x02
|
||||
#define LOG_MODE_MSG 0X03
|
||||
#define LOG_CONTROL_TUNING_MSG 0X04
|
||||
#define LOG_CONTROL_TUNING_MSG 0X04
|
||||
#define LOG_NAV_TUNING_MSG 0X05
|
||||
#define LOG_PERFORMANCE_MSG 0X06
|
||||
#define LOG_RAW_MSG 0x07
|
||||
#define LOG_CMD_MSG 0x08
|
||||
#define LOG_IMU_MSG 0x07
|
||||
#define LOG_CMD_MSG 0x08
|
||||
#define LOG_CURRENT_MSG 0x09
|
||||
#define LOG_STARTUP_MSG 0x0A
|
||||
#define TYPE_AIRSTART_MSG 0x00
|
||||
#define TYPE_GROUNDSTART_MSG 0x01
|
||||
#define TYPE_GROUNDSTART_MSG 0x01
|
||||
#define MAX_NUM_LOGS 100
|
||||
|
||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||
#define MASK_LOG_ATTITUDE_MED (1<<1)
|
||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||
#define MASK_LOG_ATTITUDE_MED (1<<1)
|
||||
#define MASK_LOG_GPS (1<<2)
|
||||
#define MASK_LOG_PM (1<<3)
|
||||
#define MASK_LOG_CTUN (1<<4)
|
||||
#define MASK_LOG_NTUN (1<<5)
|
||||
#define MASK_LOG_MODE (1<<6)
|
||||
#define MASK_LOG_RAW (1<<7)
|
||||
#define MASK_LOG_IMU (1<<7)
|
||||
#define MASK_LOG_CMD (1<<8)
|
||||
#define MASK_LOG_CUR (1<<9)
|
||||
|
||||
|
|
Loading…
Reference in New Issue