Plane: use 64-bit timestamps for dataflash logs

This commit is contained in:
Peter Barker 2015-04-30 13:40:51 +10:00 committed by Andrew Tridgell
parent 58f2bcb754
commit d7ed06816a

View File

@ -186,6 +186,7 @@ void Plane::Log_Write_Attitude(void)
struct PACKED log_Performance { struct PACKED log_Performance {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us;
uint32_t loop_time; uint32_t loop_time;
uint16_t main_loop_count; uint16_t main_loop_count;
uint32_t g_dt_max; uint32_t g_dt_max;
@ -201,6 +202,7 @@ void Plane::Log_Write_Performance()
{ {
struct log_Performance pkt = { struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG), LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
time_us : hal.scheduler->micros64(),
loop_time : millis() - perf_mon_timer, loop_time : millis() - perf_mon_timer,
main_loop_count : mainLoop_count, main_loop_count : mainLoop_count,
g_dt_max : G_Dt_max, g_dt_max : G_Dt_max,
@ -223,6 +225,7 @@ void Plane::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
struct PACKED log_Startup { struct PACKED log_Startup {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t startup_type; uint8_t startup_type;
uint16_t command_total; uint16_t command_total;
}; };
@ -231,6 +234,7 @@ void Plane::Log_Write_Startup(uint8_t type)
{ {
struct log_Startup pkt = { struct log_Startup pkt = {
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG), LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
time_us : hal.scheduler->micros64(),
startup_type : type, startup_type : type,
command_total : mission.num_commands() command_total : mission.num_commands()
}; };
@ -254,7 +258,7 @@ void Plane::Log_Write_EntireMission()
struct PACKED log_Control_Tuning { struct PACKED log_Control_Tuning {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t time_ms; uint64_t time_us;
int16_t nav_roll_cd; int16_t nav_roll_cd;
int16_t roll; int16_t roll;
int16_t nav_pitch_cd; int16_t nav_pitch_cd;
@ -270,7 +274,7 @@ void Plane::Log_Write_Control_Tuning()
Vector3f accel = ins.get_accel(); Vector3f accel = ins.get_accel();
struct log_Control_Tuning pkt = { struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG), LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
time_ms : millis(), time_us : hal.scheduler->micros64(),
nav_roll_cd : (int16_t)nav_roll_cd, nav_roll_cd : (int16_t)nav_roll_cd,
roll : (int16_t)ahrs.roll_sensor, roll : (int16_t)ahrs.roll_sensor,
nav_pitch_cd : (int16_t)nav_pitch_cd, nav_pitch_cd : (int16_t)nav_pitch_cd,
@ -290,7 +294,7 @@ void Plane::Log_Write_TECS_Tuning(void)
struct PACKED log_Nav_Tuning { struct PACKED log_Nav_Tuning {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t time_ms; uint64_t time_us;
uint16_t yaw; uint16_t yaw;
float wp_distance; float wp_distance;
int16_t target_bearing_cd; int16_t target_bearing_cd;
@ -306,7 +310,7 @@ void Plane::Log_Write_Nav_Tuning()
{ {
struct log_Nav_Tuning pkt = { struct log_Nav_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG), LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
time_ms : millis(), time_us : hal.scheduler->micros64(),
yaw : (uint16_t)ahrs.yaw_sensor, yaw : (uint16_t)ahrs.yaw_sensor,
wp_distance : auto_state.wp_distance, wp_distance : auto_state.wp_distance,
target_bearing_cd : (int16_t)nav_controller->target_bearing_cd(), target_bearing_cd : (int16_t)nav_controller->target_bearing_cd(),
@ -321,7 +325,7 @@ void Plane::Log_Write_Nav_Tuning()
struct PACKED log_Status { struct PACKED log_Status {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t timestamp; uint64_t time_us;
uint8_t is_flying; uint8_t is_flying;
float is_flying_probability; float is_flying_probability;
uint8_t armed; uint8_t armed;
@ -332,7 +336,7 @@ void Plane::Log_Write_Status()
{ {
struct log_Status pkt = { struct log_Status pkt = {
LOG_PACKET_HEADER_INIT(LOG_STATUS_MSG) LOG_PACKET_HEADER_INIT(LOG_STATUS_MSG)
,timestamp : millis() ,time_us : hal.scheduler->micros64()
,is_flying : is_flying() ,is_flying : is_flying()
,is_flying_probability : isFlyingProbability ,is_flying_probability : isFlyingProbability
,armed : hal.util->get_soft_armed() ,armed : hal.util->get_soft_armed()
@ -344,7 +348,7 @@ void Plane::Log_Write_Status()
struct PACKED log_Sonar { struct PACKED log_Sonar {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t timestamp; uint64_t time_us;
float distance; float distance;
float voltage; float voltage;
float baro_alt; float baro_alt;
@ -360,7 +364,7 @@ void Plane::Log_Write_Sonar()
#if RANGEFINDER_ENABLED == ENABLED #if RANGEFINDER_ENABLED == ENABLED
struct log_Sonar pkt = { struct log_Sonar pkt = {
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG), LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
timestamp : millis(), time_us : hal.scheduler->micros64(),
distance : (float)rangefinder.distance_cm(), distance : (float)rangefinder.distance_cm(),
voltage : rangefinder.voltage_mv()*0.001f, voltage : rangefinder.voltage_mv()*0.001f,
baro_alt : barometer.get_altitude(), baro_alt : barometer.get_altitude(),
@ -375,7 +379,7 @@ void Plane::Log_Write_Sonar()
struct PACKED log_Optflow { struct PACKED log_Optflow {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t time_ms; uint64_t time_us;
uint8_t surface_quality; uint8_t surface_quality;
float flow_x; float flow_x;
float flow_y; float flow_y;
@ -395,7 +399,7 @@ void Plane::Log_Write_Optflow()
const Vector2f &bodyRate = optflow.bodyRate(); const Vector2f &bodyRate = optflow.bodyRate();
struct log_Optflow pkt = { struct log_Optflow pkt = {
LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG), LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG),
time_ms : millis(), time_us : hal.scheduler->micros64(),
surface_quality : optflow.quality(), surface_quality : optflow.quality(),
flow_x : flowRate.x, flow_x : flowRate.x,
flow_y : flowRate.y, flow_y : flowRate.y,
@ -408,7 +412,7 @@ void Plane::Log_Write_Optflow()
struct PACKED log_Arm_Disarm { struct PACKED log_Arm_Disarm {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint32_t time_ms; uint64_t time_us;
uint8_t arm_state; uint8_t arm_state;
uint16_t arm_checks; uint16_t arm_checks;
}; };
@ -424,7 +428,7 @@ void Plane::Log_Write_Current()
void Plane::Log_Arm_Disarm() { void Plane::Log_Arm_Disarm() {
struct log_Arm_Disarm pkt = { struct log_Arm_Disarm pkt = {
LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG), LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
time_ms : millis(), time_us : hal.scheduler->micros64(),
arm_state : arming.is_armed(), arm_state : arming.is_armed(),
arm_checks : arming.get_enabled_checks() arm_checks : arming.get_enabled_checks()
}; };
@ -461,24 +465,24 @@ void Plane::Log_Write_Airspeed(void)
static const struct LogStructure log_structure[] PROGMEM = { static const struct LogStructure log_structure[] PROGMEM = {
LOG_COMMON_STRUCTURES, LOG_COMMON_STRUCTURES,
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), { LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "IHIhhhBH", "LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" }, "PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" },
{ LOG_STARTUP_MSG, sizeof(log_Startup), { LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "BH", "SType,CTot" }, "STRT", "QBH", "TimeUS,SType,CTot" },
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning), { LOG_CTUN_MSG, sizeof(log_Control_Tuning),
"CTUN", "Icccchhf", "TimeMS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,AccY" }, "CTUN", "Qcccchhf", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,AccY" },
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning), { LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "ICfccccfI", "TimeMS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" }, "NTUN", "QCfccccfI", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" },
{ LOG_SONAR_MSG, sizeof(log_Sonar), { LOG_SONAR_MSG, sizeof(log_Sonar),
"SONR", "IffffBBf", "TimeMS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" }, "SONR", "QffffBBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" },
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm), { LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
"ARM", "IHB", "TimeMS,ArmState,ArmChecks" }, "ARM", "QHB", "TimeUS,ArmState,ArmChecks" },
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP), { LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
"ATRP", "IBBcfff", "TimeMS,Type,State,Servo,Demanded,Achieved,P" }, "ATRP", "QBBcfff", "TimeUS,Type,State,Servo,Demanded,Achieved,P" },
{ LOG_STATUS_MSG, sizeof(log_Status), { LOG_STATUS_MSG, sizeof(log_Status),
"STAT", "IBfBB", "TimeMS,isFlying,isFlyProb,Armed,Safety" }, "STAT", "QBfBB", "TimeUS,isFlying,isFlyProb,Armed,Safety" },
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), { LOG_OPTFLOW_MSG, sizeof(log_Optflow),
"OF", "IBffff", "TimeMS,Qual,flowX,flowY,bodyX,bodyY" }, "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
#endif #endif
TECS_LOG_FORMAT(LOG_TECS_MSG) TECS_LOG_FORMAT(LOG_TECS_MSG)
}; };