Plane: refactor perf variables into a structure

This commit is contained in:
Andrew Tridgell 2016-04-21 11:50:13 +10:00
parent a5de231a21
commit a7006a7784
7 changed files with 41 additions and 39 deletions

View File

@ -112,19 +112,19 @@ void Plane::loop()
uint32_t timer = micros();
delta_us_fast_loop = timer - fast_loopTimer_us;
G_Dt = delta_us_fast_loop * 1.0e-6f;
perf.delta_us_fast_loop = timer - perf.fast_loopTimer_us;
G_Dt = perf.delta_us_fast_loop * 1.0e-6f;
if (delta_us_fast_loop > G_Dt_max && fast_loopTimer_us != 0) {
G_Dt_max = delta_us_fast_loop;
if (perf.delta_us_fast_loop > perf.G_Dt_max && perf.fast_loopTimer_us != 0) {
perf.G_Dt_max = perf.delta_us_fast_loop;
}
if (delta_us_fast_loop < G_Dt_min || G_Dt_min == 0) {
G_Dt_min = delta_us_fast_loop;
if (perf.delta_us_fast_loop < perf.G_Dt_min || perf.G_Dt_min == 0) {
perf.G_Dt_min = perf.delta_us_fast_loop;
}
fast_loopTimer_us = timer;
perf.fast_loopTimer_us = timer;
mainLoop_count++;
perf.mainLoop_count++;
// tell the scheduler one tick has passed
scheduler.tick();
@ -339,16 +339,16 @@ void Plane::log_perf_info()
{
if (scheduler.debug() != 0) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "G_Dt_max=%lu G_Dt_min=%lu\n",
(unsigned long)G_Dt_max,
(unsigned long)G_Dt_min);
(unsigned long)perf.G_Dt_max,
(unsigned long)perf.G_Dt_min);
}
if (should_log(MASK_LOG_PM)) {
Log_Write_Performance();
}
G_Dt_max = 0;
G_Dt_min = 0;
perf.G_Dt_max = 0;
perf.G_Dt_min = 0;
resetPerfData();
}

View File

@ -210,9 +210,9 @@ void Plane::Log_Write_Performance()
struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
time_us : AP_HAL::micros64(),
loop_time : millis() - perf_mon_timer,
main_loop_count : mainLoop_count,
g_dt_max : G_Dt_max,
loop_time : millis() - perf.start_ms,
main_loop_count : perf.mainLoop_count,
g_dt_max : perf.G_Dt_max,
gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000),
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000),

View File

@ -685,23 +685,25 @@ private:
// This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
float G_Dt = 0.02f;
// Performance monitoring
// Timer used to accrue data and trigger recording of the performanc monitoring log message
uint32_t perf_mon_timer = 0;
struct {
// Performance monitoring
// Timer used to accrue data and trigger recording of the performanc monitoring log message
uint32_t start_ms;
// The maximum and minimum main loop execution time recorded in the current performance monitoring interval
uint32_t G_Dt_max = 0;
uint32_t G_Dt_min = 0;
// The maximum and minimum main loop execution time recorded in the current performance monitoring interval
uint32_t G_Dt_max;
uint32_t G_Dt_min;
// System Timers
// Time in microseconds of start of main control loop
uint32_t fast_loopTimer_us = 0;
// System Timers
// Time in microseconds of start of main control loop
uint32_t fast_loopTimer_us;
// Number of milliseconds used in last main loop cycle
uint32_t delta_us_fast_loop = 0;
// Number of milliseconds used in last main loop cycle
uint32_t delta_us_fast_loop;
// Counter of main loop executions. Used for performance monitoring and failsafe processing
uint16_t mainLoop_count = 0;
// Counter of main loop executions. Used for performance monitoring and failsafe processing
uint16_t mainLoop_count;
} perf;
// Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED

View File

@ -23,9 +23,9 @@ void Plane::failsafe_check(void)
static bool in_failsafe;
uint32_t tnow = micros();
if (mainLoop_count != last_mainLoop_count) {
if (perf.mainLoop_count != last_mainLoop_count) {
// the main loop is running, all is OK
last_mainLoop_count = mainLoop_count;
last_mainLoop_count = perf.mainLoop_count;
last_timestamp = tnow;
in_failsafe = false;
return;

View File

@ -221,7 +221,7 @@ void Plane::update_fbwb_speed_height(void)
elevator_input = -elevator_input;
}
change_target_altitude(g.flybywire_climb_rate * elevator_input * delta_us_fast_loop * 0.0001f);
change_target_altitude(g.flybywire_climb_rate * elevator_input * perf.delta_us_fast_loop * 0.0001f);
if (is_zero(elevator_input) && !is_zero(last_elevator_input)) {
// the user has just released the elevator, lock in

View File

@ -632,10 +632,10 @@ void Plane::update_notify()
void Plane::resetPerfData(void)
{
mainLoop_count = 0;
G_Dt_max = 0;
G_Dt_min = 0;
perf_mon_timer = millis();
perf.mainLoop_count = 0;
perf.G_Dt_max = 0;
perf.G_Dt_min = 0;
perf.start_ms = millis();
}

View File

@ -360,8 +360,8 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
while(1) {
hal.scheduler->delay(20);
if (micros() - fast_loopTimer_us > 19000UL) {
fast_loopTimer_us = micros();
if (micros() - perf.fast_loopTimer_us > 19000UL) {
perf.fast_loopTimer_us = micros();
// INS
// ---
@ -421,8 +421,8 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
while(1) {
hal.scheduler->delay(20);
if (micros() - fast_loopTimer_us > 19000UL) {
fast_loopTimer_us = micros();
if (micros() - perf.fast_loopTimer_us > 19000UL) {
perf.fast_loopTimer_us = micros();
// INS
// ---