mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
GCS_MAVLink: removed perf counters
This commit is contained in:
parent
f6ec48e0e2
commit
96577b47f0
@ -580,12 +580,6 @@ private:
|
||||
// last reported radio buffer percent available
|
||||
uint8_t last_txbuf = 100;
|
||||
|
||||
// perf counters
|
||||
AP_HAL::Util::perf_counter_t _perf_packet;
|
||||
AP_HAL::Util::perf_counter_t _perf_update;
|
||||
char _perf_packet_name[16];
|
||||
char _perf_update_name[16];
|
||||
|
||||
// outbound ("deferred message") queue.
|
||||
|
||||
// "special" messages such as heartbeat, next_param etc are stored
|
||||
|
@ -144,13 +144,6 @@ bool GCS_MAVLINK::init(uint8_t instance)
|
||||
|
||||
mavlink_comm_port[chan] = _port;
|
||||
|
||||
// create performance counters
|
||||
snprintf(_perf_packet_name, sizeof(_perf_packet_name), "GCS_Packet_%u", chan);
|
||||
_perf_packet = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_packet_name);
|
||||
|
||||
snprintf(_perf_update_name, sizeof(_perf_update_name), "GCS_Update_%u", chan);
|
||||
_perf_update = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_update_name);
|
||||
|
||||
AP_SerialManager::SerialProtocol mavlink_protocol = serial_manager.get_mavlink_protocol(chan);
|
||||
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
||||
if (status == nullptr) {
|
||||
@ -1417,8 +1410,6 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us)
|
||||
uint32_t tstart_us = AP_HAL::micros();
|
||||
uint32_t now_ms = AP_HAL::millis();
|
||||
|
||||
hal.util->perf_begin(_perf_update);
|
||||
|
||||
status.packet_rx_drop_count = 0;
|
||||
|
||||
const uint16_t nbytes = _port->available();
|
||||
@ -1453,9 +1444,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us)
|
||||
// Try to get a new message
|
||||
if (mavlink_parse_char(chan, c, &msg, &status)) {
|
||||
hal.util->persistent_data.last_mavlink_msgid = msg.msgid;
|
||||
hal.util->perf_begin(_perf_packet);
|
||||
packetReceived(status, msg);
|
||||
hal.util->perf_end(_perf_packet);
|
||||
parsed_packet = true;
|
||||
gcs_alternative_active[chan] = false;
|
||||
alternative.last_mavlink_ms = now_ms;
|
||||
@ -1562,8 +1551,6 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us)
|
||||
try_send_message_stats.statustext_last_sent_ms = now16_ms;
|
||||
}
|
||||
#endif
|
||||
|
||||
hal.util->perf_end(_perf_update);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user