mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Rover: use PerfInfo for performance monitoring
This commit is contained in:
parent
044bc9adf0
commit
9511e72113
@ -85,6 +85,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(accel_cal_update, 10, 100),
|
||||
SCHED_TASK_CLASS(DataFlash_Class, &rover.DataFlash, periodic_tasks, 50, 300),
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 50, 50),
|
||||
SCHED_TASK(perf_update, 0.1, 75),
|
||||
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 100),
|
||||
SCHED_TASK(stats_update, 1, 100),
|
||||
SCHED_TASK(crash_check, 10, 1000),
|
||||
@ -115,6 +116,10 @@ void Rover::setup()
|
||||
|
||||
// initialise the main loop scheduler
|
||||
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks));
|
||||
|
||||
// setup initial performance counters
|
||||
perf_info.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||
perf_info.reset();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -127,14 +132,13 @@ void Rover::loop()
|
||||
|
||||
const uint32_t timer = AP_HAL::micros();
|
||||
|
||||
delta_us_fast_loop = timer - fast_loopTimer_us;
|
||||
G_Dt = delta_us_fast_loop * 1.0e-6f;
|
||||
// check loop time
|
||||
perf_info.check_loop_time(timer - fast_loopTimer_us);
|
||||
|
||||
G_Dt = (timer - fast_loopTimer_us) * 1.0e-6f;
|
||||
fast_loopTimer_us = timer;
|
||||
|
||||
if (delta_us_fast_loop > G_Dt_max) {
|
||||
G_Dt_max = delta_us_fast_loop;
|
||||
}
|
||||
|
||||
// for mainloop failure monitoring
|
||||
mainLoop_count++;
|
||||
|
||||
// tell the scheduler one tick has passed
|
||||
@ -277,6 +281,23 @@ void Rover::update_aux(void)
|
||||
SRV_Channels::enable_aux_servos();
|
||||
}
|
||||
|
||||
void Rover::perf_update()
|
||||
{
|
||||
if (should_log(MASK_LOG_PM)) {
|
||||
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());
|
||||
}
|
||||
perf_info.reset();
|
||||
}
|
||||
|
||||
/*
|
||||
once a second events
|
||||
*/
|
||||
@ -305,18 +326,6 @@ void Rover::one_second_loop(void)
|
||||
|
||||
counter++;
|
||||
|
||||
// write perf data every 20s
|
||||
if (counter % 10 == 0) {
|
||||
if (scheduler.debug() != 0) {
|
||||
hal.console->printf("G_Dt_max=%u\n", G_Dt_max);
|
||||
}
|
||||
if (should_log(MASK_LOG_PM)) {
|
||||
Log_Write_Performance();
|
||||
}
|
||||
G_Dt_max = 0;
|
||||
resetPerfData();
|
||||
}
|
||||
|
||||
// save compass offsets once a minute
|
||||
if (counter >= 60) {
|
||||
if (g.compass_enabled) {
|
||||
|
@ -7,9 +7,9 @@
|
||||
struct PACKED log_Performance {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint32_t loop_time;
|
||||
uint16_t main_loop_count;
|
||||
uint32_t g_dt_max;
|
||||
uint16_t num_long_running;
|
||||
uint16_t num_loops;
|
||||
uint32_t max_time;
|
||||
int16_t gyro_drift_x;
|
||||
int16_t gyro_drift_y;
|
||||
int16_t gyro_drift_z;
|
||||
@ -24,9 +24,9 @@ void Rover::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,
|
||||
num_long_running : perf_info.get_num_long_running(),
|
||||
num_loops : perf_info.get_num_loops(),
|
||||
max_time : perf_info.get_max_time(),
|
||||
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),
|
||||
|
@ -59,6 +59,7 @@
|
||||
#include <AP_Relay/AP_Relay.h> // APM relay
|
||||
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
|
||||
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
||||
#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
|
||||
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
|
||||
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
@ -212,6 +213,9 @@ private:
|
||||
|
||||
AP_ServoRelayEvents ServoRelayEvents{relay};
|
||||
|
||||
// loop performance monitoring:
|
||||
AP::PerfInfo perf_info;
|
||||
|
||||
// The rover's current location
|
||||
struct Location current_loc;
|
||||
|
||||
@ -330,17 +334,9 @@ private:
|
||||
// This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
|
||||
float G_Dt;
|
||||
|
||||
// Performance monitoring
|
||||
// Timer used to accrue data and trigger recording of the performance monitoring log message
|
||||
int32_t perf_mon_timer;
|
||||
// The maximum main loop execution time, in microseconds, recorded in the current performance monitoring interval
|
||||
uint32_t G_Dt_max;
|
||||
|
||||
// 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;
|
||||
// Counter of main loop executions. Used for performance monitoring and failsafe processing
|
||||
uint16_t mainLoop_count;
|
||||
|
||||
@ -401,6 +397,7 @@ private:
|
||||
private:
|
||||
|
||||
// APMrover2.cpp
|
||||
void perf_update();
|
||||
void stats_update();
|
||||
void ahrs_update();
|
||||
void update_alt();
|
||||
@ -560,7 +557,6 @@ private:
|
||||
bool set_mode(Mode &new_mode, mode_reason_t reason);
|
||||
bool mavlink_set_mode(uint8_t mode);
|
||||
void startup_INS_ground(void);
|
||||
void resetPerfData(void);
|
||||
void check_usb_mux(void);
|
||||
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
||||
void notify_mode(const Mode *new_mode);
|
||||
|
@ -262,13 +262,6 @@ void Rover::startup_INS_ground(void)
|
||||
ahrs.reset();
|
||||
}
|
||||
|
||||
void Rover::resetPerfData(void) {
|
||||
mainLoop_count = 0;
|
||||
G_Dt_max = 0;
|
||||
perf_mon_timer = millis();
|
||||
}
|
||||
|
||||
|
||||
void Rover::check_usb_mux(void)
|
||||
{
|
||||
bool usb_check = hal.gpio->usb_connected();
|
||||
|
Loading…
Reference in New Issue
Block a user