mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-19 21:19:06 +08:00
Simulator: Add performance counter for incoming packet interval
This commit is contained in:
parent
fb3fade653
commit
62763904f2
@ -230,6 +230,7 @@ private:
|
||||
_perf_gps(perf_alloc_once(PC_ELAPSED, "sim_gps_delay")),
|
||||
_perf_airspeed(perf_alloc_once(PC_ELAPSED, "sim_airspeed_delay")),
|
||||
_perf_sim_delay(perf_alloc_once(PC_ELAPSED, "sim_network_delay")),
|
||||
_perf_sim_interval(perf_alloc(PC_INTERVAL, "sim_network_interval")),
|
||||
_accel_pub(nullptr),
|
||||
_baro_pub(nullptr),
|
||||
_gyro_pub(nullptr),
|
||||
@ -270,6 +271,7 @@ private:
|
||||
perf_counter_t _perf_gps;
|
||||
perf_counter_t _perf_airspeed;
|
||||
perf_counter_t _perf_sim_delay;
|
||||
perf_counter_t _perf_sim_interval;
|
||||
|
||||
// uORB publisher handlers
|
||||
orb_advert_t _accel_pub;
|
||||
|
||||
@ -248,6 +248,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
|
||||
uint64_t timestamp = ts.tv_sec * 1000 * 1000 + ts.tv_nsec / 1000;
|
||||
|
||||
perf_set(_perf_sim_delay, timestamp - sim_timestamp);
|
||||
perf_count(_perf_sim_interval);
|
||||
|
||||
if (publish) {
|
||||
publish_sensor_topics(&imu);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user