full ARHS update, EKF3 at 1KHz. Also I tested 2Khz but in that case it is required to move out a lot of tasks from AP_Scheduler to threads. This requires a lots of efforts however
Iām just trying to build the latest chibios work for the pixhawk cube hardware, and Iām not sure what repo, branch and build target/s to use ā¦ ?
Iām trying:
repo: https://github.com/bugobliterator/ardupilot-chibios
branch: pr-chibios-fmuv4
target: ./waf configure --board chibios
what did I missā¦?
this gives me:
source not found: ālibraries/AP_HAL_ChibiOS/hwdef/chibios/hwdef.datā in bld(group=ādynamic_sourcesā, target=[āhwdef.hā, āapj.prototypeā], idx=5, meths=[āprocess_ruleā, āprocess_sourceā], rule=āpython ${AP_HAL_ROOT}/hwdef/scripts/chibios_hwdef.py -D ${BUILDROOT} ${AP_HAL_ROOT}/hwdef/${BOARD}/hwdef.datā, _name=āhwdef.h,apj.prototypeā, source=ālibraries/AP_HAL_ChibiOS/hwdef/chibios/hwdef.datā, path=/Users/buzz/UAV/ardupilot, posted=True, features=[]) in /Users/buzz/UAV/ardupilot
@DavidBuzz you can use ardupilot master, and build like this:
./waf configure --board fmuv3
./waf plane --upload
Nice! did it have GPS lock and compass? (most of the CPU cost is mag and gps fusion)
Iād be interested in seeing a DF log if you have one
thx tridge, that worked. !
hmm, interesting, I just tested this with ChibiOS and was surprised to find that 1kHz works nicely
APM: PERF: 0/10000 max=2199 min=599 avg=1048 sd=214
APM: PERF: 0/10000 max=2597 min=593 avg=1047 sd=215
APM: PERF: 0/10000 max=2199 min=599 avg=1048 sd=214
APM: PERF: 0/10000 max=2202 min=603 avg=1048 sd=216
APM: PERF: 0/10000 max=2209 min=598 avg=1048 sd=215
APM: PERF: 0/10000 max=2208 min=598 avg=1048 sd=215
this is on a Pixhawk2.1 cube with 3 IMUs, two compasses, uBlox GPS, 1kHz main loop rate and 4 EKFs running
ie.
EK2_ENABLE=1
EK2_IMU_MASK=3
EK3_ENABLE=1
EK3_IMU_MASK=3
so, I thought Iād try 2kHz, and yes, it works, but has some troubles with the comms with the IOMCU:
APM: PERF: 1/20000 max=7103 min=11 avg=717 sd=149
APM: PERF: 0/20000 max=1799 min=576 avg=740 sd=135
no reply for 54/0/14
APM: PERF: 0/20000 max=1697 min=579 avg=741 sd=134
the 1.5MBit serial port we use to talk to the IOMCU isnāt fast enough for 2kHz, which is why we get the above error msgs. On something like PixRacer that has no IOMCU I expect it would be fine.
with BRD_IO_ENABLE=0 to disable the IOMCU 2kHz works nicely on a pixhawk 2.1 with 4 EKFs:
APM: PERF: 0/20000 max=1699 min=575 avg=707 sd=132
APM: PERF: 0/20000 max=1797 min=579 avg=704 sd=134
APM: PERF: 0/20000 max=1898 min=580 avg=704 sd=135
APM: PERF: 0/20000 max=1700 min=577 avg=704 sd=135
APM: PERF: 0/20000 max=1598 min=577 avg=703 sd=134
APM: PERF: 0/20000 max=1702 min=577 avg=704 sd=134
APM: PERF: 0/20000 max=1607 min=576 avg=704 sd=135
there does seem to be a problem with MAVLink scheduling on usb though - not a long enough time slice to get mavlink messages out consistently at 2kHz
Also note the āavgā column in the above, its 704us, which means averaging 1420Hz, so its not really doing 2kHz
The zero scheduling misses is just because it uses a threshold for a miss based on 400Hz
averaging 1420Hz
mean time of Copter::fast_loop() with single IMU is ~270uS, so it runs fine at 2kHz, but MPU6000 gives data at 1kHz so 2kHz is useless for me.
PS, >APM: PERF: 0/10000 max=2208 min=598 avg=1048 sd=215
btw, what about sd=10 as above?
I have been wondering if we should run the gyro sampling on the MPU6000 at a higher rate. It canāt do accel over 1kHz, but IIRC it can do gyro at up to 8kHz.
yep, Iām getting a lot more variance, but Iām also running 4 EKFs, 3 IMUs and 2 compasses
I should setup a board with a single IMU. Do you have a GPS and mag hooked up and with GPS lock?
Yes, and log write too. I use not true GPS but recorded NMEA stream for debug.
UPD. And with built-in OSD too
[quote=āPedals2Paddles, post:20, topic:20491, full:trueā]
The procedures for building with Nuttx are unchanged and still work. And thatās what people should still use unless they want to be test pilots for ChibiOS.
Make based builds are no longer even used or supported in ArduPilot. ā¦
[/quote]many THX
the comment on make I think is not correct though, luckily
Leonard has got some good flight results running copter with ChibiOS at 1kHz on a PH2.1 cube. Iām going to extend support in AP_InertialSensor to allow for 2kHz and he will try that soon
Make is still there but is no longer being supported or updated. It has been replaced by WAF. Probably half the board types are not even included in make anymore. All of the linux board types have been removed from make completely. ChibiOS builds are not in make and they wonāt be. If you want to build ChibiOS, you will need to use WAF.
I just ran the build with the latest from @tridgeās branch and loaded onto my Solo. Spectacular!
- RC & PWM I/O has been restored
- Soloās mavlink gimbal is now fully operational.
- GoPro controls work through the mavlink gimbal as they should
- As before, Smart battery is working in all respects
- Dataflash logging over mavlink is working
The performance monitor data is astounding! The Solo is very heavy load on the Pixhawkās performance. As you can see, with the Nuttx / px4 firmware, it is extremely overtaxed at all times. The gimbal and logging take a heavy toll on it. Massive overruns at all times. With ChibiOS, well the the numbers speak for themselves. Overruns went from 30-50% with px4/nuttx, down to 0.125%. I donāt even need to describe the results.
ArduCoper master 3.6-Dev // Nuttx & PX4
PERF: 1316/4000 max=6659 min=2119 avg=2953 sd=597
PERF: 1280/4000 max=8157 min=1882 avg=2952 sd=616
PERF: 1275/4000 max=7370 min=2014 avg=2958 sd=637
PERF: 1313/4000 max=7256 min=1905 avg=2960 sd=607
PERF: 1328/4000 max=6748 min=1942 avg=2958 sd=600
PERF: 1313/4001 max=6854 min=1934 avg=2953 sd=584
ArduCopter 3.6-Dev // ChibiOS
PERF: 1/4000 max=3004 min=2200 avg=2501 sd=86
PERF: 2/4000 max=3308 min=2125 avg=2501 sd=96
PERF: 1/4000 max=3102 min=2197 avg=2501 sd=90
PERF: 2/4000 max=3102 min=2098 avg=2501 sd=88
PERF: 5/4000 max=3795 min=2104 avg=2505 sd=99
PERF: 0/4000 max=2998 min=2104 avg=2501 sd=94
PERF: 0/4000 max=2888 min=2100 avg=2500 sd=82
Thanks Matt! Really nice to hear.
Now the big question, have you flown it?
Not yet. Perhaps this weekend.
WOW, THIS is good stuff.
Whats the state of CAN on the chibios portā¦ just curious ā¦?
Itās under works, I will have initial implementation out soon.
In November I was trying to bring up the night_ghost port of ArduPlane (pre-merge-into-Master) on an Omnibus F4 V3, but with limited success, particularly on the I2C airspeed sensor front. End goal is a very lightweight but fully functional full house e-glider with everything ArduPlane has to offer. See attached planned layout, and photos of the flight controller itself. Does it seem that the ChibiOS-based ArduPlane is now ready to handle everything shown here? If so, I will dive in. If not, I can wait.
Thrilled with what Tridge, Sid and others have accomplished here.
Kelly