Copter: use AP::PerfInfo library

This commit is contained in:
Peter Barker 2017-11-13 13:07:47 +11:00 committed by Francisco Ferreira
parent fd543fce6d
commit 04c9e966e0
4 changed files with 18 additions and 24 deletions

View File

@ -178,7 +178,7 @@ void Copter::setup()
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks));
// setup initial performance counters
perf_info_reset();
perf_info.reset();
fast_loopTimer = AP_HAL::micros();
}
@ -196,14 +196,14 @@ void Copter::perf_update(void)
Log_Write_Performance();
if (scheduler.debug()) {
gcs().send_text(MAV_SEVERITY_WARNING, "PERF: %u/%u max=%lu min=%lu avg=%lu sd=%lu",
(unsigned)perf_info_get_num_long_running(),
(unsigned)perf_info_get_num_loops(),
(unsigned long)perf_info_get_max_time(),
(unsigned long)perf_info_get_min_time(),
(unsigned long)perf_info_get_avg_time(),
(unsigned long)perf_info_get_stddev_time());
(unsigned)perf_info.get_num_long_running(),
(unsigned)perf_info.get_num_loops(),
(unsigned long)perf_info.get_max_time(),
(unsigned long)perf_info.get_min_time(),
(unsigned long)perf_info.get_avg_time(),
(unsigned long)perf_info.get_stddev_time());
}
perf_info_reset();
perf_info.reset();
pmTest1 = 0;
}
@ -223,7 +223,7 @@ void Copter::loop()
uint32_t timer = micros();
// check loop time
perf_info_check_loop_time(timer - fast_loopTimer);
perf_info.check_loop_time(timer - fast_loopTimer);
// used by PI Loops
G_Dt = (float)(timer - fast_loopTimer) / 1000000.0f;

View File

@ -78,6 +78,7 @@
#include <AC_Fence/AC_Fence.h> // Arducopter Fence library
#include <AC_Avoidance/AC_Avoid.h> // Arducopter stop at fence library
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
@ -475,6 +476,9 @@ private:
// filtered pilot's throttle input used to cancel landing if throttle held high
LowPassFilterFloat rc_throttle_control_in_filter;
// loop performance monitoring:
AP::PerfInfo perf_info = AP::PerfInfo::create();
// 3D Location vectors
// Current location of the copter (altitude is relative to home)
Location_Class current_loc;
@ -1032,16 +1036,6 @@ private:
void calc_wp_bearing();
void calc_home_distance_and_bearing();
void run_autopilot();
void perf_info_reset();
void perf_ignore_this_loop();
void perf_info_check_loop_time(uint32_t time_in_micros);
uint16_t perf_info_get_num_loops();
uint32_t perf_info_get_max_time();
uint32_t perf_info_get_min_time();
uint16_t perf_info_get_num_long_running();
uint32_t perf_info_get_num_dropped();
uint32_t perf_info_get_avg_time();
uint32_t perf_info_get_stddev_time();
Vector3f pv_location_to_vector(const Location& loc);
float pv_alt_above_origin(float alt_above_home_cm);
float pv_alt_above_home(float alt_above_origin_cm);

View File

@ -208,13 +208,13 @@ void Copter::Log_Write_Performance()
struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
time_us : AP_HAL::micros64(),
num_long_running : perf_info_get_num_long_running(),
num_loops : perf_info_get_num_loops(),
max_time : perf_info_get_max_time(),
num_long_running : perf_info.get_num_long_running(),
num_loops : perf_info.get_num_loops(),
max_time : perf_info.get_max_time(),
pm_test : pmTest1,
i2c_lockup_count : 0,
ins_error_count : ins.error_count(),
log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(),
log_dropped : DataFlash.num_dropped() - perf_info.get_num_dropped(),
hal.util->available_memory()
};
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));

View File

@ -207,7 +207,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
failsafe_enable();
// perf monitor ignores delay due to arming
perf_ignore_this_loop();
perf_info.ignore_this_loop();
// flag exiting this function
in_arm_motors = false;