mirror of https://github.com/ArduPilot/ardupilot
Copter: replace Log_Write_Motors with Log_Write_RCOU
This commit is contained in:
parent
45ab18f131
commit
10d6a9a34e
|
@ -1153,8 +1153,8 @@ static void ten_hz_logging_loop()
|
||||||
if (g.log_bitmask & MASK_LOG_RCIN) {
|
if (g.log_bitmask & MASK_LOG_RCIN) {
|
||||||
DataFlash.Log_Write_RCIN();
|
DataFlash.Log_Write_RCIN();
|
||||||
}
|
}
|
||||||
if (g.log_bitmask & MASK_LOG_MOTORS) {
|
if (g.log_bitmask & MASK_LOG_RCOUT) {
|
||||||
Log_Write_Motors();
|
DataFlash.Log_Write_RCOUT();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -44,7 +44,7 @@ print_log_menu(void)
|
||||||
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(PSTR(" IMU"));
|
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_CMD) cliSerial->printf_P(PSTR(" CMD"));
|
||||||
if (g.log_bitmask & MASK_LOG_CURRENT) 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_RCOUT) cliSerial->printf_P(PSTR(" RCOUT"));
|
||||||
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
|
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
|
||||||
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(PSTR(" PID"));
|
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(PSTR(" PID"));
|
||||||
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
|
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
|
||||||
|
@ -136,7 +136,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
||||||
TARG(IMU);
|
TARG(IMU);
|
||||||
TARG(CMD);
|
TARG(CMD);
|
||||||
TARG(CURRENT);
|
TARG(CURRENT);
|
||||||
TARG(MOTORS);
|
TARG(RCOUT);
|
||||||
TARG(OPTFLOW);
|
TARG(OPTFLOW);
|
||||||
TARG(PID);
|
TARG(PID);
|
||||||
TARG(COMPASS);
|
TARG(COMPASS);
|
||||||
|
@ -232,62 +232,6 @@ static void Log_Write_Current()
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Motors {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
#if FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
|
|
||||||
int16_t motor_out[8];
|
|
||||||
#elif FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME
|
|
||||||
int16_t motor_out[6];
|
|
||||||
#elif FRAME_CONFIG == HELI_FRAME
|
|
||||||
int16_t motor_out[6];
|
|
||||||
#else // quads & TRI_FRAME
|
|
||||||
int16_t motor_out[4];
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
// Write an Motors packet
|
|
||||||
static void Log_Write_Motors()
|
|
||||||
{
|
|
||||||
struct log_Motors pkt = {
|
|
||||||
LOG_PACKET_HEADER_INIT(LOG_MOTORS_MSG),
|
|
||||||
#if FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
|
|
||||||
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_2],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_3],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_4],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_5],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_6],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_7],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_8]}
|
|
||||||
#elif FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME
|
|
||||||
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_2],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_3],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_4],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_5],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_6]}
|
|
||||||
#elif FRAME_CONFIG == HELI_FRAME
|
|
||||||
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_2],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_3],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_4],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_7],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_8]}
|
|
||||||
#elif FRAME_CONFIG == TRI_FRAME
|
|
||||||
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_2],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_4],
|
|
||||||
g.rc_4.radio_out}
|
|
||||||
#else // QUAD frame
|
|
||||||
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_2],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_3],
|
|
||||||
motors.motor_out[AP_MOTORS_MOT_4]}
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
||||||
}
|
|
||||||
|
|
||||||
struct PACKED log_Optflow {
|
struct PACKED log_Optflow {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
int16_t dx;
|
int16_t dx;
|
||||||
|
@ -773,21 +717,6 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
||||||
#endif
|
#endif
|
||||||
{ LOG_CURRENT_MSG, sizeof(log_Current),
|
{ LOG_CURRENT_MSG, sizeof(log_Current),
|
||||||
"CURR", "hIhhhf", "ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot" },
|
"CURR", "hIhhhf", "ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot" },
|
||||||
|
|
||||||
#if FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
|
|
||||||
{ LOG_MOTORS_MSG, sizeof(log_Motors),
|
|
||||||
"MOT", "hhhhhhhh", "Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,Mot7,Mot8" },
|
|
||||||
#elif FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME
|
|
||||||
{ LOG_MOTORS_MSG, sizeof(log_Motors),
|
|
||||||
"MOT", "hhhhhh", "Mot1,Mot2,Mot3,Mot4,Mot5,Mot6" },
|
|
||||||
#elif FRAME_CONFIG == HELI_FRAME
|
|
||||||
{ LOG_MOTORS_MSG, sizeof(log_Motors),
|
|
||||||
"MOT", "hhhhh", "Mot1,Mot2,Mot3,Mot4,GGain" },
|
|
||||||
#else
|
|
||||||
{ LOG_MOTORS_MSG, sizeof(log_Motors),
|
|
||||||
"MOT", "hhhh", "Mot1,Mot2,Mot3,Mot4" },
|
|
||||||
#endif
|
|
||||||
|
|
||||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
||||||
"OF", "hhBccffee", "Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch" },
|
"OF", "hhBccffee", "Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch" },
|
||||||
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
||||||
|
@ -888,7 +817,6 @@ static void Log_Write_Event(uint8_t id){}
|
||||||
static void Log_Write_Optflow() {}
|
static void Log_Write_Optflow() {}
|
||||||
static void Log_Write_Nav_Tuning() {}
|
static void Log_Write_Nav_Tuning() {}
|
||||||
static void Log_Write_Control_Tuning() {}
|
static void Log_Write_Control_Tuning() {}
|
||||||
static void Log_Write_Motors() {}
|
|
||||||
static void Log_Write_Performance() {}
|
static void Log_Write_Performance() {}
|
||||||
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) {}
|
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) {}
|
||||||
static void Log_Write_Camera() {}
|
static void Log_Write_Camera() {}
|
||||||
|
|
|
@ -1007,8 +1007,8 @@
|
||||||
# define LOG_CURRENT ENABLED
|
# define LOG_CURRENT ENABLED
|
||||||
#endif
|
#endif
|
||||||
// quad motor PWMs
|
// quad motor PWMs
|
||||||
#ifndef LOG_MOTORS
|
#ifndef LOG_RCOUT
|
||||||
# define LOG_MOTORS DISABLED
|
# define LOG_RCOUT DISABLED
|
||||||
#endif
|
#endif
|
||||||
// optical flow
|
// optical flow
|
||||||
#ifndef LOG_OPTFLOW
|
#ifndef LOG_OPTFLOW
|
||||||
|
@ -1041,7 +1041,7 @@
|
||||||
LOGBIT(IMU) | \
|
LOGBIT(IMU) | \
|
||||||
LOGBIT(CMD) | \
|
LOGBIT(CMD) | \
|
||||||
LOGBIT(CURRENT) | \
|
LOGBIT(CURRENT) | \
|
||||||
LOGBIT(MOTORS) | \
|
LOGBIT(RCOUT) | \
|
||||||
LOGBIT(OPTFLOW) | \
|
LOGBIT(OPTFLOW) | \
|
||||||
LOGBIT(PID) | \
|
LOGBIT(PID) | \
|
||||||
LOGBIT(COMPASS) | \
|
LOGBIT(COMPASS) | \
|
||||||
|
|
|
@ -279,7 +279,6 @@ enum ap_message {
|
||||||
#define LOG_CMD_MSG 0x08
|
#define LOG_CMD_MSG 0x08
|
||||||
#define LOG_CURRENT_MSG 0x09
|
#define LOG_CURRENT_MSG 0x09
|
||||||
#define LOG_STARTUP_MSG 0x0A
|
#define LOG_STARTUP_MSG 0x0A
|
||||||
#define LOG_MOTORS_MSG 0x0B
|
|
||||||
#define LOG_OPTFLOW_MSG 0x0C
|
#define LOG_OPTFLOW_MSG 0x0C
|
||||||
#define LOG_EVENT_MSG 0x0D
|
#define LOG_EVENT_MSG 0x0D
|
||||||
#define LOG_PID_MSG 0x0E
|
#define LOG_PID_MSG 0x0E
|
||||||
|
@ -307,7 +306,7 @@ enum ap_message {
|
||||||
#define MASK_LOG_IMU (1<<7)
|
#define MASK_LOG_IMU (1<<7)
|
||||||
#define MASK_LOG_CMD (1<<8)
|
#define MASK_LOG_CMD (1<<8)
|
||||||
#define MASK_LOG_CURRENT (1<<9)
|
#define MASK_LOG_CURRENT (1<<9)
|
||||||
#define MASK_LOG_MOTORS (1<<10)
|
#define MASK_LOG_RCOUT (1<<10)
|
||||||
#define MASK_LOG_OPTFLOW (1<<11)
|
#define MASK_LOG_OPTFLOW (1<<11)
|
||||||
#define MASK_LOG_PID (1<<12)
|
#define MASK_LOG_PID (1<<12)
|
||||||
#define MASK_LOG_COMPASS (1<<13)
|
#define MASK_LOG_COMPASS (1<<13)
|
||||||
|
|
Loading…
Reference in New Issue