Browse Source

Copter: make PERF info message into a STATUSTEXT message

this makes it appear properly in tlogs. Also show both min and max
loop times
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
191d803968
  1. 15
      ArduCopter/ArduCopter.pde
  2. 5
      ArduCopter/GCS_Mavlink.pde
  3. 31
      ArduCopter/perf_info.pde

15
ArduCopter/ArduCopter.pde

@ -216,6 +216,8 @@ static bool in_log_download; @@ -216,6 +216,8 @@ static bool in_log_download;
////////////////////////////////////////////////////////////////////////////////
static void update_events(void);
static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
static void gcs_send_text_fmt(const prog_char_t *fmt, ...);
////////////////////////////////////////////////////////////////////////////////
// Dataflash
@ -890,6 +892,10 @@ void setup() @@ -890,6 +892,10 @@ void setup()
// initialise the main loop scheduler
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
// setup initial performance counters
perf_info_reset();
fast_loopTimer = hal.scheduler->micros();
}
/*
@ -915,10 +921,11 @@ static void perf_update(void) @@ -915,10 +921,11 @@ static void perf_update(void)
if (should_log(MASK_LOG_PM))
Log_Write_Performance();
if (scheduler.debug()) {
cliSerial->printf_P(PSTR("PERF: %u/%u %lu\n"),
(unsigned)perf_info_get_num_long_running(),
(unsigned)perf_info_get_num_loops(),
(unsigned long)perf_info_get_max_time());
gcs_send_text_fmt(PSTR("PERF: %u/%u %lu %lu\n"),
(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());
}
perf_info_reset();
pmTest1 = 0;

5
ArduCopter/GCS_Mavlink.pde

@ -16,9 +16,6 @@ static bool gcs_out_of_time; @@ -16,9 +16,6 @@ static bool gcs_out_of_time;
// check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_ ## id ## _LEN) return false
// prototype this for use inside the GCS class
static void gcs_send_text_fmt(const prog_char_t *fmt, ...);
static void gcs_send_heartbeat(void)
{
gcs_send_message(MSG_HEARTBEAT);
@ -1704,7 +1701,7 @@ static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str) @@ -1704,7 +1701,7 @@ static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
* only one fits in the queue, so if you send more than one before the
* last one gets into the serial buffer then the old one will be lost
*/
void gcs_send_text_fmt(const prog_char_t *fmt, ...)
static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
{
va_list arg_list;
gcs[0].pending_status.severity = (uint8_t)SEVERITY_LOW;

31
ArduCopter/perf_info.pde

@ -11,27 +11,29 @@ @@ -11,27 +11,29 @@
# define PERF_INFO_OVERTIME_THRESHOLD_MICROS 10500
#endif
uint16_t perf_info_loop_count;
uint32_t perf_info_max_time;
uint16_t perf_info_long_running;
bool perf_ignore_loop = false;
static uint16_t perf_info_loop_count;
static uint32_t perf_info_max_time;
static uint32_t perf_info_min_time;
static uint16_t perf_info_long_running;
static bool perf_ignore_loop = false;
// perf_info_reset - reset all records of loop time to zero
void perf_info_reset()
static void perf_info_reset()
{
perf_info_loop_count = 0;
perf_info_max_time = 0;
perf_info_min_time = 0;
perf_info_long_running = 0;
}
// perf_ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
void perf_ignore_this_loop()
static void perf_ignore_this_loop()
{
perf_ignore_loop = true;
}
// perf_info_check_loop_time - check latest loop time vs min, max and overtime threshold
void perf_info_check_loop_time(uint32_t time_in_micros)
static void perf_info_check_loop_time(uint32_t time_in_micros)
{
perf_info_loop_count++;
@ -44,25 +46,34 @@ void perf_info_check_loop_time(uint32_t time_in_micros) @@ -44,25 +46,34 @@ void perf_info_check_loop_time(uint32_t time_in_micros)
if( time_in_micros > perf_info_max_time) {
perf_info_max_time = time_in_micros;
}
if( perf_info_min_time == 0 || time_in_micros < perf_info_min_time) {
perf_info_min_time = time_in_micros;
}
if( time_in_micros > PERF_INFO_OVERTIME_THRESHOLD_MICROS ) {
perf_info_long_running++;
}
}
// perf_info_get_long_running_percentage - get number of long running loops as a percentage of the total number of loops
uint16_t perf_info_get_num_loops()
static uint16_t perf_info_get_num_loops()
{
return perf_info_loop_count;
}
// perf_info_get_max_time - return maximum loop time (in microseconds)
uint32_t perf_info_get_max_time()
static uint32_t perf_info_get_max_time()
{
return perf_info_max_time;
}
// perf_info_get_max_time - return maximum loop time (in microseconds)
static uint32_t perf_info_get_min_time()
{
return perf_info_min_time;
}
// perf_info_get_num_long_running - get number of long running loops
uint16_t perf_info_get_num_long_running()
static uint16_t perf_info_get_num_long_running()
{
return perf_info_long_running;
}

Loading…
Cancel
Save