CPU overload on CUAV V5+ large vehicle

Hello everyone,

I built a hexacopter with a length of 130 cm and a weight of 12 kg using Hobbywing X6 Plus motors, an MK15 controller, and a CUAV V5+ flight controller. However, when I try to take off this drone in auto mode or in guided mode, the CPU overloads, and a CPU error is displayed on the HUD screen of the mission planner. The drone then switches to RTL mode and land. After checking the logs, I found that the CPU reached 100 percent. two or three time

Does anyone know what the problem might be and what changes should be made?

  1. update to ArduCopter 4.5.5.
  2. post a .bin log file
3 Likes

i using arducopter 4.6.0

I’ve also been thinking about this for some time. I’ve found all recent copter versions give high CPU usage on the CUAV V5 Nano - about 5% higher than an old Pixhawk1-1M just idling (not armed). At idle the CPU can be at 48% to 52%.
You can see in this old log the CPU goes to 100% for much of the flights, and there is some small amount of uncommanded movements at times. There was some twitching and fake telemetry messages such as “disarmed” when it wasnt.
I dont have a more recent flight log since I stopped using the V5 Nano for flight, but have tested a lot of firmware versions without flying, and with minimum features, all with the same result.

For comparison a Cube Orange configured the same as the Nano idles at about 32% and only goes a few percent higher during flight.
Plane firmware idles at about 4% on every flight controller I have. I dont have anything set up to fly for a better test. From plane logs I’ve seen the usage can go up to 10% or a bit more, but nothing near 100%

1 Like

Does @SYS/tasks.txt tell you where the CPU is going?

1 Like

i haven’t this file on my drone files :frowning:

i use v5+ its work on quad pretty good but on hexa…
can i decrease main loop frequency to 300hz?
Can this help?

all cuav product have this issue?

Tasks just has “TasksV2”, basically empty, but Threads has:

ISR           PRI=255 sp=0x20020000 STACK=1312/1536
ArduCopter    PRI=182 sp=0x20020600 STACK=3976/7168
idle          PRI=  1 sp=0x2003F478 STACK=288/496
UART_RX       PRI= 60 sp=0x2007CFB8 STACK=856/1200
OTG1          PRI= 60 sp=0x2007C070 STACK=344/752
monitor       PRI=183 sp=0x2003BA18 STACK=1104/1456
timer         PRI=181 sp=0x2003CFD8 STACK=1600/1968
rcout         PRI=181 sp=0x2003C5F8 STACK=680/944
rcin          PRI=177 sp=0x2003C008 STACK=1080/1456
io            PRI= 58 sp=0x2003B028 STACK=1576/2480
storage       PRI= 59 sp=0x2003C9E8 STACK=912/1456
UART2         PRI= 60 sp=0x2007B0E8 STACK=272/752
UART3         PRI= 60 sp=0x2007A5A0 STACK=264/752
UART1         PRI= 60 sp=0x200799D8 STACK=352/752
UART4         PRI= 60 sp=0x20078E10 STACK=480/752
OTG2          PRI= 60 sp=0x20077EC8 STACK=344/752
SPI4          PRI=181 sp=0x20076A78 STACK=944/1456
log_io        PRI= 59 sp=0x200613F8 STACK=1520/2016
I2C0          PRI=176 sp=0x2005F860 STACK=984/1456
SPI1          PRI=181 sp=0x2005CDE0 STACK=824/1456
FTP           PRI= 58 sp=0x20053708 STACK=1032/2992

With SCHED_DEBUG,2 I get messages like:

9/08/2024 7:43:19 AM : PERF: 0/4000 [2569:2430] F=400Hz sd=6 Ex=0
9/08/2024 7:43:09 AM : PERF: 0/4000 [2555:2443] F=400Hz sd=6 Ex=0
9/08/2024 7:42:59 AM : PERF: 0/4000 [2551:2449] F=399Hz sd=7 Ex=0
9/08/2024 7:42:49 AM : PERF: 0/4000 [2556:2444] F=400Hz sd=7 Ex=0
9/08/2024 7:42:41 AM : PERF: 0/4000 [2553:2447] F=400Hz sd=7 Ex=0

With SCHED_DEBUG,3 I get messages like:

9/08/2024 7:47:10 AM : PERF: 25/4000 [3226:2189] F=398Hz sd=92 Ex=100
9/08/2024 7:46:59 AM : PERF: 49/4000 [3341:2162] F=396Hz sd=102 Ex=100
9/08/2024 7:46:49 AM : PERF: 42/4000 [3252:2200] F=397Hz sd=97 Ex=0

Let me know if there is anything else I can check on or a procedure to follow.

@wolfin as a test I reduced loop rate to 200Hz and CPU usage drops to 30% to 35% which looks good, but I’d be doubtful about safe flying with copter without at least retuning or extensive testing. 300Hz gave me about 40% CPU usage.
You would have to try 300Hz on a copter you are prepared to have damaged if it doesnt work out so well.

This may be a problem with the V5 flight controllers, which are based on FMUv5. I’m not aware of it happening on V7 or anything else, but we may lack data too.

1 Like

try tasks a few times - it needs the first call to setup the timings. To see thread CPU usage you would need to build with --enable-stats

2 Likes

Hi wolfin
Try a flight with these and no other changes, so it should be totally safe:

INS_ENABLE_MASK,3
INS_USE3,0

then send a link to the .bin log if you can.
These drop the CPU usage down to around 38% to 44% on the bench, (down from about 70% with all my last known-flying config)

1 Like

Sorry Andy, Tasks didnt come good.
Are you able to do me a CUAV V5 Nano build with that option, current Stable version please.

I dont have a copter to put this FC onto but bench testing is enough to see the differences so far.

1 Like

@andyp1per This may be due to the fact that FMU v5 uses an F7 processor, but it uses a complete Ardupilot, while FMU V2/V3 has deleted many new drivers and functions. I have used other manufacturers’ FMU v5 products and obtained the same results. It seems that we should delete some unnecessary programs. Good performance for the H7, I didn’t find any issues in the X7.

1 Like

https://www.dropbox.com/scl/fi/5boqzdnh00dynodg5yq8z/arducopter.apj?rlkey=2srmxfq6906dbg4369pw8b7pu&dl=0

1 Like

Unfortunately I don’t have any v5 flight controllers from any manufacturer so its difficult for me to test

1 Like

Thanks for the build Andy.
With all my normal parameters and 3 IMUs enabled…
The headline act seems to be Copter::read_AHRS TOT=58.8%
With Copter::update_flight_mode using up a bit more time than I expected

I can easily run tests, but I’m not set up to compile the firmware myself.

ThreadsV2
ISR           PRI=255 sp=0x20020000 STACK=1276/1536 LOAD= 2.0%
ArduCopter    PRI=182 sp=0x20020600 STACK=3976/7168 LOAD=39.9%
idle          PRI=  1 sp=0x2003F590 STACK= 296/ 504 LOAD= 9.6%
UART_RX       PRI= 60 sp=0x2007CF98 STACK= 864/1208 LOAD= 0.6%
OTG1          PRI= 60 sp=0x2007C030 STACK= 344/ 760 LOAD= 0.1%
monitor       PRI=183 sp=0x2003BA38 STACK=1112/1464 LOAD= 0.3%
timer         PRI=181 sp=0x2003D078 STACK=1544/1976 LOAD= 1.1%
rcout         PRI=181 sp=0x2003C658 STACK= 568/ 952 LOAD= 5.2%
rcin          PRI=177 sp=0x2003C048 STACK=1080/1464 LOAD= 0.3%
io            PRI= 58 sp=0x2003B028 STACK=1624/2488 LOAD= 0.3%*
storage       PRI= 59 sp=0x2003CA68 STACK= 944/1464 LOAD= 0.1%
UART2         PRI= 60 sp=0x2007B088 STACK= 488/ 760 LOAD= 0.1%
UART3         PRI= 60 sp=0x2007A520 STACK= 344/ 760 LOAD= 0.2%
UART1         PRI= 60 sp=0x200799B8 STACK= 352/ 760 LOAD= 0.1%
UART4         PRI= 60 sp=0x20078E50 STACK= 488/ 760 LOAD= 0.1%
MSP           PRI= 59 sp=0x20078288 STACK= 976/1464 LOAD= 0.2%
SPI4          PRI=181 sp=0x20076E40 STACK= 952/1464 LOAD= 0.3%
OSD           PRI= 59 sp=0x200763A8 STACK=1304/1720 LOAD= 0.1%
log_io        PRI= 59 sp=0x20061728 STACK=1080/2016 LOAD= 0.1%
I2C0          PRI=176 sp=0x2005F868 STACK= 968/1464 LOAD= 0.2%
SPI1          PRI=181 sp=0x2005E9C8 STACK= 768/1464 LOAD=38.2%
Scripting     PRI=  2 sp=0x200589F8 STACK=15296/17848 LOAD= 0.1%
FTP           PRI= 58 sp=0x2004A3F0 STACK=1040/3000 LOAD= 0.2%
TasksV2
AP_InertialSensor::update*       MIN=  30 MAX= 276 AVG=  45 OVR=  0 SLP=  0, TOT= 2.1%
Copter::run_rate_controller*     MIN=  21 MAX= 252 AVG=  30 OVR=  0 SLP=  0, TOT= 1.4%
Copter::motors_output*           MIN=  67 MAX= 485 AVG= 137 OVR=  0 SLP=  0, TOT= 6.4%
Copter::read_AHRS*               MIN= 464 MAX=2825 AVG=1270 OVR=  2 SLP=  0, TOT=58.8%
Copter::read_inertia*            MIN=   5 MAX= 124 AVG=  12 OVR=  0 SLP=  0, TOT= 0.6%
Copter::check_ekf_reset*         MIN=   3 MAX=  85 AVG=  10 OVR=  0 SLP=  0, TOT= 0.4%
Copter::update_flight_mode*      MIN= 134 MAX= 595 AVG= 299 OVR=  0 SLP=  0, TOT=14.1%
Copter::update_home_from_EKF*    MIN=   2 MAX= 108 AVG=   9 OVR=  0 SLP=  0, TOT= 0.4%
Copter::update_land_and_crash_de MIN=   5 MAX= 246 AVG=  22 OVR=  0 SLP=  0, TOT= 1.1%
Copter::update_rangefinder_terra MIN=   2 MAX= 112 AVG=   8 OVR=  0 SLP=  0, TOT= 0.4%
AP_Mount::update_fast*           MIN=   1 MAX= 127 AVG=   3 OVR=  0 SLP=  0, TOT= 0.1%
Copter::Log_Video_Stabilisation* MIN=   1 MAX= 115 AVG=   4 OVR=  0 SLP=  0, TOT= 0.2%
AP_GyroFFT::sample_gyros*        MIN=   1 MAX= 117 AVG=   3 OVR=  0 SLP=  0, TOT= 0.1%
Copter::rc_loop                  MIN=   6 MAX= 220 AVG=  18 OVR=  0 SLP=  0, TOT= 0.9%
Copter::throttle_loop            MIN=   7 MAX= 110 AVG=  13 OVR=  1 SLP=  0, TOT= 0.1%
Copter::fence_check              MIN=   3 MAX=  19 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
AP_GPS::update                   MIN=   9 MAX= 178 AVG=  37 OVR=  0 SLP=  0, TOT= 0.2%
AP_OpticalFlow::update           MIN=   1 MAX=  94 AVG=   4 OVR=  1 SLP=  0, TOT= 0.1%
Copter::update_batt_compass      MIN=  25 MAX= 151 AVG=  78 OVR=  2 SLP=  0, TOT= 0.1%
RC_Channels::read_aux_all        MIN=   7 MAX=   8 AVG=   7 OVR=  0 SLP=  0, TOT= 0.0%
Copter::arm_motors_check         MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::auto_disarm_check        MIN=   2 MAX=   3 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
Copter::auto_trim                MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::read_rangefinder         MIN=  10 MAX= 154 AVG=  30 OVR=  1 SLP=  0, TOT= 0.1%
AP_Proximity::update             MIN=   2 MAX= 122 AVG=   9 OVR=  6 SLP=  0, TOT= 0.2%
AP_Beacon::update                MIN=   1 MAX= 122 AVG=   8 OVR= 15 SLP=  0, TOT= 0.4%
AP_Airspeed::update              MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::update_altitude          MIN=  21 MAX= 264 AVG=  92 OVR=  2 SLP=  0, TOT= 0.1%
Copter::run_nav_updates          MIN=   2 MAX=  21 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
Copter::update_throttle_hover    MIN=   2 MAX=  56 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
ModeSmartRTL::save_position      MIN=   3 MAX=   3 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AC_Sprayer::update               MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::three_hz_loop            MIN=   5 MAX=   5 AVG=   5 OVR=  0 SLP=  0, TOT= 0.0%
AP_ServoRelayEvents::update_even MIN=   3 MAX=  51 AVG=   7 OVR=  0 SLP=  0, TOT= 0.0%
AP_Baro::accumulate              MIN=   1 MAX=  82 AVG=   9 OVR=  0 SLP=  0, TOT= 0.1%
Copter::update_precland          MIN=   1 MAX= 183 AVG=   7 OVR=  9 SLP=  0, TOT= 0.3%
Copter::loop_rate_logging        MIN=   2 MAX= 118 AVG=   6 OVR=  8 SLP=  0, TOT= 0.3%
Compass::cal_update              MIN=   2 MAX=  79 AVG=   4 OVR=  0 SLP=  0, TOT= 0.1%
AP_Notify::update                MIN=   7 MAX= 166 AVG=  26 OVR=  0 SLP=  0, TOT= 0.1%
Copter::one_hz_loop              MIN=   0 MAX=   0 AVG=   0 OVR=  0 SLP=  0, TOT= 0.0%
Copter::ekf_check                MIN=   2 MAX=   3 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
Copter::check_vibration          MIN=   4 MAX=   5 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
Copter::gpsglitch_check          MIN=   2 MAX=   3 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
Copter::takeoff_check            MIN=   2 MAX=  82 AVG=   6 OVR=  1 SLP=  0, TOT= 0.0%
Copter::landinggear_update       MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::standby_update           MIN=   3 MAX= 112 AVG=   7 OVR=  1 SLP=  0, TOT= 0.1%
Copter::lost_vehicle_check       MIN=   5 MAX=   5 AVG=   5 OVR=  0 SLP=  0, TOT= 0.0%
GCS::update_receive              MIN=  14 MAX= 255 AVG=  43 OVR= 10 SLP=  0, TOT= 2.1%
GCS::update_send                 MIN=  23 MAX= 457 AVG=  80 OVR= 14 SLP=  0, TOT= 3.7%
AP_Mount::update                 MIN=   1 MAX=  69 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
AP_Camera::update                MIN=   2 MAX=  83 AVG=   8 OVR=  1 SLP=  0, TOT= 0.1%
Copter::ten_hz_logging_loop      MIN= 193 MAX= 466 AVG= 395 OVR=  5 SLP=  0, TOT= 0.5%
Copter::twentyfive_hz_logging    MIN=   4 MAX= 149 AVG=  26 OVR=  1 SLP=  0, TOT= 0.1%
AP_Logger::periodic_tasks        MIN=  13 MAX= 261 AVG=  43 OVR= 12 SLP=  0, TOT= 2.1%
AP_InertialSensor::periodic      MIN=   1 MAX= 143 AVG=   5 OVR=  9 SLP=  0, TOT= 0.2%
AP_Scheduler::update_logging     MIN=  62 MAX=  62 AVG=  62 OVR=  0 SLP=  0, TOT= 0.0%
AP_RPM::update                   MIN=   1 MAX=  23 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_TempCalibration::update       MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::avoidance_adsb_update    MIN=   8 MAX=  54 AVG=  16 OVR=  0 SLP=  0, TOT= 0.0%
Copter::terrain_update           MIN=   2 MAX=  71 AVG=  13 OVR=  0 SLP=  0, TOT= 0.0%
AP_Gripper::update               MIN=   2 MAX=   3 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_Winch::update                 MIN=   2 MAX=  36 AVG=   5 OVR=  0 SLP=  0, TOT= 0.0%
AP_Button::update                MIN=   2 MAX=  31 AVG=  11 OVR=  0 SLP=  0, TOT= 0.0%
AP_Stats::update                 MIN=   4 MAX=   4 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
AP_NMEA_Output::update           MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_RunCam::update                MIN=   1 MAX=  66 AVG=   3 OVR=  1 SLP=  0, TOT= 0.0%
AP_GyroFFT::update               MIN=   1 MAX= 188 AVG=  12 OVR= 19 SLP=  0, TOT= 0.6%
AP_GyroFFT::update_parameters    MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::update_dynamic_notch MIN=   2 MAX= 214 AVG=  17 OVR= 10 SLP=  0, TOT= 0.8%
AP_VideoTX::update               MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Tramp::update                 MIN=   1 MAX=  42 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::send_watchdog_reset_ MIN=   3 MAX=   3 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_ESC_Telem::update             MIN=  44 MAX= 381 AVG= 136 OVR= 40 SLP=  0, TOT= 1.8%
AP_Generator::update             MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::publish_osd_info     MIN=   9 MAX=   9 AVG=   9 OVR=  0 SLP=  0, TOT= 0.0%
AP_TemperatureSensor::update     MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::accel_cal_update     MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AC_Fence::update                 MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_AIS::update                   MIN=   1 MAX=  55 AVG=  19 OVR=  0 SLP=  0, TOT= 0.0%
AP_EFI::update                   MIN=   3 MAX=  60 AVG=   9 OVR=  0 SLP=  0, TOT= 0.1%
AP_Vehicle::one_Hz_update        MIN=   2 MAX=   2 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::check_motor_noise    MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Filters::update               MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::update_arming        MIN= 972 MAX= 972 AVG= 972 OVR=  1 SLP=  0, TOT= 0.2%

Another reboot and check gives
Copter::read_AHRS* MIN= 376 MAX=3848 AVG=1301 OVR= 74 SLP= 0, TOT=63.7%
and slightly lower Copter::update_flight_mode

1 Like

read_AHRS() is the EKF update so you would expect that to be expensive. The suspicious one is SPI1 - 38% is pretty high for that. I wonder if we are getting some SPI collisions.

2 Likes

Thank you for your response and the time you took.
No, I cannot take the risk of this device crashing.
Are you sure that if I use a 300 Hz loop, it will lead to a crash?
Are there any safer ways to test it?"

Hi xfacta
Okay, I will test this configuration as soon as possible and will inform you of the results.

exactly in my task file read_AHRS took 62% of cpu @andyp1per

TasksV2
AP_InertialSensor::update*       MIN=  17 MAX=  36 AVG=  20 OVR=  0 SLP=  0, TOT= 1.4%
Copter::run_rate_controller*     MIN=  20 MAX=  41 AVG=  23 OVR=  0 SLP=  0, TOT= 1.6%
Copter::motors_output*           MIN=  79 MAX= 193 AVG=  85 OVR=  0 SLP=  0, TOT= 5.7%
Copter::read_AHRS*               MIN= 381 MAX=2466 AVG= 932 OVR=  0 SLP=  0, TOT=61.9%
Copter::read_inertia*            MIN=   5 MAX=  98 AVG=  12 OVR=  0 SLP=  0, TOT= 0.8%
Copter::check_ekf_reset*         MIN=   3 MAX=  87 AVG=   8 OVR=  0 SLP=  0, TOT= 0.5%
Copter::update_flight_mode*      MIN=  52 MAX= 337 AVG= 106 OVR=  0 SLP=  0, TOT= 7.1%
Copter::update_home_from_EKF*    MIN=   2 MAX= 107 AVG=   5 OVR=  0 SLP=  0, TOT= 0.3%
Copter::update_land_and_crash_de MIN=   5 MAX= 136 AVG=  12 OVR=  0 SLP=  0, TOT= 0.8%
Copter::update_rangefinder_terra MIN=   2 MAX= 162 AVG=   6 OVR=  0 SLP=  0, TOT= 0.4%
AP_Mount::update_fast*           MIN=   1 MAX= 145 AVG=   2 OVR=  0 SLP=  0, TOT= 0.1%
Copter::Log_Video_Stabilisation* MIN=   1 MAX=  92 AVG=   4 OVR=  0 SLP=  0, TOT= 0.2%
AP_GyroFFT::sample_gyros*        MIN=   1 MAX= 113 AVG=   2 OVR=  0 SLP=  0, TOT= 0.1%
Copter::rc_loop                  MIN=   6 MAX= 156 AVG=  15 OVR=  0 SLP=  0, TOT= 1.0%
Copter::throttle_loop            MIN=   6 MAX=  92 AVG=  16 OVR=  4 SLP=  0, TOT= 0.1%
Copter::fence_check              MIN=   2 MAX=  58 AVG=   5 OVR=  0 SLP=  0, TOT= 0.0%
AP_GPS::update                   MIN=  11 MAX= 758 AVG=  81 OVR= 38 SLP=  0, TOT= 0.9%
AP_OpticalFlow::update           MIN=   1 MAX= 157 AVG=   5 OVR=  0 SLP=  0, TOT= 0.3%
Copter::update_batt_compass      MIN=  23 MAX= 170 AVG=  47 OVR=  5 SLP=  0, TOT= 0.1%
RC_Channels::read_aux_all        MIN=   6 MAX=  87 AVG=  13 OVR=  6 SLP=  0, TOT= 0.0%
Copter::arm_motors_check         MIN=   1 MAX=  66 AVG=   2 OVR=  1 SLP=  0, TOT= 0.0%
Copter::auto_disarm_check        MIN=   1 MAX=  54 AVG=   4 OVR=  1 SLP=  0, TOT= 0.0%
Copter::auto_trim                MIN=   1 MAX=  31 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::read_rangefinder         MIN=   6 MAX= 121 AVG=  19 OVR=  2 SLP=  0, TOT= 0.1%
AP_Proximity::update             MIN=   2 MAX= 167 AVG=  10 OVR=115 SLP=  0, TOT= 0.6%
AP_Beacon::update                MIN=   1 MAX=  81 AVG=   2 OVR=  8 SLP=  0, TOT= 0.1%
AP_Airspeed::update              MIN=   1 MAX=  39 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::update_altitude          MIN=  19 MAX= 125 AVG=  35 OVR=  3 SLP=  0, TOT= 0.1%
Copter::run_nav_updates          MIN=   1 MAX=  68 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
Copter::update_throttle_hover    MIN=   1 MAX=  72 AVG=   3 OVR=  0 SLP=  0, TOT= 0.1%
ModeSmartRTL::save_position      MIN=   3 MAX=  51 AVG=   8 OVR=  0 SLP=  0, TOT= 0.0%
AC_Sprayer::update               MIN=   1 MAX=   6 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
Copter::three_hz_loop            MIN=   4 MAX=  37 AVG=   6 OVR=  0 SLP=  0, TOT= 0.0%
AP_ServoRelayEvents::update_even MIN=   1 MAX=  96 AVG=   4 OVR=  2 SLP=  0, TOT= 0.1%
Copter::update_precland          MIN=   1 MAX= 120 AVG=   7 OVR= 70 SLP=  0, TOT= 0.5%
Copter::loop_rate_logging        MIN=   2 MAX= 144 AVG=   5 OVR= 38 SLP=  0, TOT= 0.4%
Compass::cal_update              MIN=   1 MAX=  91 AVG=   4 OVR=  0 SLP=  0, TOT= 0.1%
AP_Notify::update                MIN=   6 MAX= 117 AVG=  14 OVR=  0 SLP=  0, TOT= 0.1%
Copter::one_hz_loop              MIN=  41 MAX= 152 AVG=  94 OVR=  3 SLP=  0, TOT= 0.0%
Copter::ekf_check                MIN=   1 MAX=  41 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
Copter::check_vibration          MIN=   3 MAX=  73 AVG=   8 OVR=  5 SLP=  0, TOT= 0.0%
Copter::gpsglitch_check          MIN=   2 MAX=  61 AVG=   4 OVR=  1 SLP=  0, TOT= 0.0%
Copter::takeoff_check            MIN=   2 MAX=  63 AVG=   6 OVR=  9 SLP=  0, TOT= 0.1%
Copter::landinggear_update       MIN=   1 MAX=  34 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
Copter::standby_update           MIN=   1 MAX= 136 AVG=   5 OVR=  4 SLP=  0, TOT= 0.1%
Copter::lost_vehicle_check       MIN=   3 MAX=  92 AVG=   8 OVR=  3 SLP=  0, TOT= 0.0%
GCS::update_receive              MIN=  17 MAX= 456 AVG=  46 OVR=  8 SLP=  0, TOT= 3.1%
GCS::update_send                 MIN=  32 MAX= 524 AVG=  78 OVR=  2 SLP=  0, TOT= 5.2%
AP_Mount::update                 MIN=   1 MAX=  49 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_Camera::update                MIN=   2 MAX=  54 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
Copter::ten_hz_logging_loop      MIN= 129 MAX= 313 AVG= 204 OVR=  0 SLP=  0, TOT= 0.4%
Copter::twentyfive_hz_logging    MIN=   3 MAX=  74 AVG=  10 OVR=  0 SLP=  0, TOT= 0.1%
AP_Logger::periodic_tasks        MIN=  11 MAX= 167 AVG=  25 OVR=  0 SLP=  0, TOT= 1.7%
AP_InertialSensor::periodic      MIN=   1 MAX=  55 AVG=   2 OVR=  1 SLP=  0, TOT= 0.1%
AP_Scheduler::update_logging     MIN=  16 MAX=  16 AVG=  16 OVR=  0 SLP=  0, TOT= 0.0%
AP_RPM::update                   MIN=   1 MAX=  55 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_TempCalibration::update       MIN=   1 MAX=  51 AVG=   5 OVR=  0 SLP=  0, TOT= 0.0%
Copter::avoidance_adsb_update    MIN=  10 MAX=  84 AVG=  24 OVR=  0 SLP=  0, TOT= 0.1%
Copter::terrain_update           MIN=  82 MAX= 283 AVG= 153 OVR= 62 SLP=  0, TOT= 0.3%
AP_Winch::update                 MIN=   2 MAX=  60 AVG=   4 OVR=  1 SLP=  0, TOT= 0.1%
AP_Button::update                MIN=   1 MAX=  22 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_Custom::update_custom         MIN=   1 MAX=  58 AVG=   4 OVR=  7 SLP=  0, TOT= 0.0%
AP_NMEA_Output::update           MIN=   1 MAX=  48 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_RunCam::update                MIN=   1 MAX=  37 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_GyroFFT::update               MIN=   1 MAX= 110 AVG=   6 OVR= 24 SLP=  0, TOT= 0.4%
AP_GyroFFT::update_parameters    MIN=   1 MAX=  22 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::update_dynamic_notch MIN=   2 MAX=  84 AVG=   4 OVR=  0 SLP=  0, TOT= 0.3%
AP_VideoTX::update               MIN=   1 MAX=  46 AVG=   7 OVR=  0 SLP=  0, TOT= 0.0%
AP_Tramp::update                 MIN=   1 MAX=  38 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::send_watchdog_reset_ MIN=   2 MAX=   2 AVG=   2 OVR=  0 SLP=  0, TOT= 0.0%
AP_ESC_Telem::update             MIN=  31 MAX= 219 AVG=  59 OVR=298 SLP=  0, TOT= 1.3%
AP_Generator::update             MIN=   1 MAX=  37 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::publish_osd_info     MIN=   3 MAX=  47 AVG=   8 OVR=  1 SLP=  0, TOT= 0.0%
AP_TemperatureSensor::update     MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::accel_cal_update     MIN=   1 MAX=  67 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
AC_Fence::update                 MIN=   1 MAX=  58 AVG=   4 OVR=  0 SLP=  0, TOT= 0.0%
AP_AIS::update                   MIN=   1 MAX=  49 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_EFI::update                   MIN=   3 MAX=  64 AVG=   7 OVR=  0 SLP=  0, TOT= 0.1%
AP_Gripper::update               MIN=   1 MAX=  30 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::one_Hz_update        MIN=  16 MAX=  63 AVG=  23 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::check_motor_noise    MIN=   1 MAX=   2 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Filters::update               MIN=   1 MAX=   1 AVG=   1 OVR=  0 SLP=  0, TOT= 0.0%
AP_Stats::update                 MIN=   3 MAX=   4 AVG=   3 OVR=  0 SLP=  0, TOT= 0.0%
AP_Vehicle::update_arming        MIN= 475 MAX= 584 AVG= 510 OVR=  8 SLP=  0, TOT= 0.1%

Do you need it? I will send you a cuav v5

1 Like