Sub: replace NTUN with PSC logging
This commit is contained in:
parent
4a74b1b5e5
commit
c857f8332b
@ -204,7 +204,7 @@ void Sub::ten_hz_logging_loop()
|
|||||||
DataFlash.Log_Write_RCOUT();
|
DataFlash.Log_Write_RCOUT();
|
||||||
}
|
}
|
||||||
if (should_log(MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
|
if (should_log(MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
|
||||||
Log_Write_Nav_Tuning();
|
pos_control.write_log();
|
||||||
}
|
}
|
||||||
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
|
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
|
||||||
DataFlash.Log_Write_Vibration(ins);
|
DataFlash.Log_Write_Vibration(ins);
|
||||||
|
@ -45,47 +45,6 @@ void Sub::Log_Write_Optflow()
|
|||||||
#endif // OPTFLOW == ENABLED
|
#endif // OPTFLOW == ENABLED
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Nav_Tuning {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
uint64_t time_us;
|
|
||||||
float desired_pos_x;
|
|
||||||
float desired_pos_y;
|
|
||||||
float pos_x;
|
|
||||||
float pos_y;
|
|
||||||
float desired_vel_x;
|
|
||||||
float desired_vel_y;
|
|
||||||
float vel_x;
|
|
||||||
float vel_y;
|
|
||||||
float desired_accel_x;
|
|
||||||
float desired_accel_y;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Write an Nav Tuning packet
|
|
||||||
void Sub::Log_Write_Nav_Tuning()
|
|
||||||
{
|
|
||||||
const Vector3f &pos_target = pos_control.get_pos_target();
|
|
||||||
const Vector3f &vel_target = pos_control.get_vel_target();
|
|
||||||
const Vector3f &accel_target = pos_control.get_accel_target();
|
|
||||||
const Vector3f &position = inertial_nav.get_position();
|
|
||||||
const Vector3f &velocity = inertial_nav.get_velocity();
|
|
||||||
|
|
||||||
struct log_Nav_Tuning pkt = {
|
|
||||||
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
|
|
||||||
time_us : AP_HAL::micros64(),
|
|
||||||
desired_pos_x : pos_target.x,
|
|
||||||
desired_pos_y : pos_target.y,
|
|
||||||
pos_x : position.x,
|
|
||||||
pos_y : position.y,
|
|
||||||
desired_vel_x : vel_target.x,
|
|
||||||
desired_vel_y : vel_target.y,
|
|
||||||
vel_x : velocity.x,
|
|
||||||
vel_y : velocity.y,
|
|
||||||
desired_accel_x : accel_target.x,
|
|
||||||
desired_accel_y : accel_target.y
|
|
||||||
};
|
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
||||||
}
|
|
||||||
|
|
||||||
struct PACKED log_Control_Tuning {
|
struct PACKED log_Control_Tuning {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
@ -389,8 +348,6 @@ const struct LogStructure Sub::log_structure[] = {
|
|||||||
LOG_COMMON_STRUCTURES,
|
LOG_COMMON_STRUCTURES,
|
||||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
||||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" },
|
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" },
|
||||||
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
|
||||||
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY", "smmmmnnnnoo", "FBBBBBBBBBB" },
|
|
||||||
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
||||||
"CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
|
"CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
|
||||||
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
||||||
@ -430,7 +387,6 @@ void Sub::log_init(void)
|
|||||||
#else // LOGGING_ENABLED
|
#else // LOGGING_ENABLED
|
||||||
|
|
||||||
void Sub::do_erase_logs(void) {}
|
void Sub::do_erase_logs(void) {}
|
||||||
void Sub::Log_Write_Nav_Tuning() {}
|
|
||||||
void Sub::Log_Write_Control_Tuning() {}
|
void Sub::Log_Write_Control_Tuning() {}
|
||||||
void Sub::Log_Write_Performance() {}
|
void Sub::Log_Write_Performance() {}
|
||||||
void Sub::Log_Write_Attitude(void) {}
|
void Sub::Log_Write_Attitude(void) {}
|
||||||
|
@ -493,7 +493,6 @@ private:
|
|||||||
void gcs_check_input(void);
|
void gcs_check_input(void);
|
||||||
void do_erase_logs(void);
|
void do_erase_logs(void);
|
||||||
void Log_Write_Optflow();
|
void Log_Write_Optflow();
|
||||||
void Log_Write_Nav_Tuning();
|
|
||||||
void Log_Write_Control_Tuning();
|
void Log_Write_Control_Tuning();
|
||||||
void Log_Write_Performance();
|
void Log_Write_Performance();
|
||||||
void Log_Write_Attitude();
|
void Log_Write_Attitude();
|
||||||
|
@ -105,7 +105,6 @@ enum LoggingParameters {
|
|||||||
TYPE_AIRSTART_MSG,
|
TYPE_AIRSTART_MSG,
|
||||||
TYPE_GROUNDSTART_MSG,
|
TYPE_GROUNDSTART_MSG,
|
||||||
LOG_CONTROL_TUNING_MSG,
|
LOG_CONTROL_TUNING_MSG,
|
||||||
LOG_NAV_TUNING_MSG,
|
|
||||||
LOG_OPTFLOW_MSG,
|
LOG_OPTFLOW_MSG,
|
||||||
LOG_EVENT_MSG,
|
LOG_EVENT_MSG,
|
||||||
LOG_ERROR_MSG,
|
LOG_ERROR_MSG,
|
||||||
|
Loading…
Reference in New Issue
Block a user