mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: log RATE with ATT
This commit is contained in:
parent
d9b65cec22
commit
b679fd0be0
@ -1038,8 +1038,6 @@ static void ten_hz_logging_loop()
|
|||||||
{
|
{
|
||||||
if (should_log(MASK_LOG_ATTITUDE_MED)) {
|
if (should_log(MASK_LOG_ATTITUDE_MED)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
}
|
|
||||||
if (should_log(MASK_LOG_RATE)) {
|
|
||||||
Log_Write_Rate();
|
Log_Write_Rate();
|
||||||
}
|
}
|
||||||
if (should_log(MASK_LOG_MOT)) {
|
if (should_log(MASK_LOG_MOT)) {
|
||||||
@ -1068,6 +1066,7 @@ static void fifty_hz_logging_loop()
|
|||||||
#if HIL_MODE == HIL_MODE_DISABLED
|
#if HIL_MODE == HIL_MODE_DISABLED
|
||||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
|
Log_Write_Rate();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (should_log(MASK_LOG_IMU)) {
|
if (should_log(MASK_LOG_IMU)) {
|
||||||
|
@ -364,20 +364,6 @@ static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
|
|||||||
DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd);
|
DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd);
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Rate {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
uint32_t time_ms;
|
|
||||||
float control_roll;
|
|
||||||
float roll;
|
|
||||||
float roll_out;
|
|
||||||
float control_pitch;
|
|
||||||
float pitch;
|
|
||||||
float pitch_out;
|
|
||||||
float control_yaw;
|
|
||||||
float yaw;
|
|
||||||
float yaw_out;
|
|
||||||
};
|
|
||||||
|
|
||||||
struct PACKED log_Mot {
|
struct PACKED log_Mot {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint32_t time_ms;
|
uint32_t time_ms;
|
||||||
@ -406,6 +392,20 @@ static void Log_Write_Attitude()
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
struct PACKED log_Rate {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
uint32_t time_ms;
|
||||||
|
float control_roll;
|
||||||
|
float roll;
|
||||||
|
float roll_out;
|
||||||
|
float control_pitch;
|
||||||
|
float pitch;
|
||||||
|
float pitch_out;
|
||||||
|
float control_yaw;
|
||||||
|
float yaw;
|
||||||
|
float yaw_out;
|
||||||
|
};
|
||||||
|
|
||||||
// Write an rate packet
|
// Write an rate packet
|
||||||
static void Log_Write_Rate()
|
static void Log_Write_Rate()
|
||||||
{
|
{
|
||||||
|
@ -686,7 +686,6 @@
|
|||||||
MASK_LOG_OPTFLOW | \
|
MASK_LOG_OPTFLOW | \
|
||||||
MASK_LOG_COMPASS | \
|
MASK_LOG_COMPASS | \
|
||||||
MASK_LOG_CAMERA | \
|
MASK_LOG_CAMERA | \
|
||||||
MASK_LOG_RATE | \
|
|
||||||
MASK_LOG_MOT
|
MASK_LOG_MOT
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -259,8 +259,7 @@ enum FlipState {
|
|||||||
#define MASK_LOG_INAV (1<<14) // deprecated
|
#define MASK_LOG_INAV (1<<14) // deprecated
|
||||||
#define MASK_LOG_CAMERA (1<<15)
|
#define MASK_LOG_CAMERA (1<<15)
|
||||||
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
|
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
|
||||||
#define MASK_LOG_RATE (1UL<<17)
|
#define MASK_LOG_MOT (1UL<<17)
|
||||||
#define MASK_LOG_MOT (1UL<<18)
|
|
||||||
#define MASK_LOG_ANY 0xFFFF
|
#define MASK_LOG_ANY 0xFFFF
|
||||||
|
|
||||||
// DATA - event logging
|
// DATA - event logging
|
||||||
|
Loading…
Reference in New Issue
Block a user