This board runs without issues with stable, somewhere in-between caused the following to malfunction:
Compass is not correctly detected, it receives data and it's possible to see the changes on GUI, but calibration is unreachable at the moment.
Gyros and Accels, once calibrated, show an offset with default rotation settings, differing with 'stable' lectures (e.g. offset in pitch -20-30° and roll 5°-10°, some drift is present).
This is the output of dmesg for release/1.15:
HW arch: MRO_PIXRACERPRO
PX4 git-hash: a294e011ab1aac3fc3a2239c33eaa1326b914dab
PX4 version: 1.15.0 80 (17760384)
OS: NuttX
OS version: Release 11.0.0 (184549631)
OS git-hash: 5d74bc138955e6f010a38e0f87f34e9a9019aecc
Build datetime: Aug 8 2024 18:19:19
Build uri: localhost
Build variant: default
Toolchain: GNU GCC, 9.3.1 20200408 (release)
PX4GUID: 000600000000343439393432510e0036003e
MCU: STM32H7[4|5]xxx, rev. V
ERROR [bsondump] open '/fs/mtd_caldata' failed (2)
New /fs/mtd_caldata size is:
ERROR [bsondump] open '/fs/mtd_caldata' failed (2)
INFO [param] selected parameter default file /fs/mtd_params
INFO [param] importing from '/fs/mtd_params'
INFO [parameters] BSON document size 1218 bytes, decoded 1218 bytes (INT32:19, FLOAT:36)
INFO [param] selected parameter backup file /fs/microsd/parameters_backup.bson
Board architecture defaults: /etc/init.d/rc.board_arch_defaults
Board defaults: /etc/init.d/rc.board_defaults
Loading airframe: /etc/init.d/airframes/4001_quad_x
INFO [dataman] data manager file '/fs/microsd/dataman' size is 68528 bytes
Board sensors: /etc/init.d/rc.board_sensors
icm20602 #0 on SPI bus 1 rotation 8
ERROR [SPI_I2C] bmi088: no instance started (no device on bus?)
bmi085_accel #0 on SPI bus 5 rotation 8
bmi085_gyro #0 on SPI bus 5 rotation 8
icm20948 #0 on SPI bus 1 rotation 8
dps310 #0 on SPI bus 2
ekf2 [623:237]
Starting GPS Port on /dev/ttyS3
Conflicting config for /dev/ttyS3
Starting MAVLink on /dev/ttyS1
INFO [mavlink] mode: Normal, data rate: 1200 B/s on /dev/ttyS1 @ 57600B
INFO [cdcacm_autostart] Starting CDC/ACM autostart
Board extras: /etc/init.d/rc.board_extras
INFO [logger] logger started (mode=all)
INFO [uavcan] Node ID 1, bitrate 1000000
Upload the latest main binary to a mRo Pixracer Pro
Perform the calibration of all sensors
Place the board on a leveled surface
Observe error
The issue has been reproduced in other brand new mRo Pixracer Pro boards.
Expected behavior
Once placed on a leveled surface, the artificial horizon should not present an offset corresponding to the pitch/roll axis. Compass should be able to be recognized by PX4 and available for calibration.
This is the output of dmesg for v1.14.3:
nsh> dmesg
HW arch: MRO_PIXRACERPRO
PX4 git-hash: 1dacb4cdef2d7145754fc788fa8dc482eed74b40
PX4 version: 1.14.3 0 (17695488)
OS: NuttX
OS version: Release 11.0.0 (184549631)
OS git-hash: de41e7feaeffaec3ce65327e9569e8fdb553ca3d
Build datetime: May 30 2024 03:20:39
Build uri: localhost
Build variant: default
Toolchain: GNU GCC, 9.3.1 20200408 (release)
PX4GUID: 000600000000343439393432510e0036003e
MCU: STM32H7[4|5]xxx, rev. V
INFO [param] selected parameter default file /fs/mtd_params
INFO [param] importing from '/fs/mtd_params'
INFO [parameters] BSON document size 1170 bytes, decoded 1170 bytes (INT32:16, FLOAT:36)
INFO [param] selected parameter backup file /fs/microsd/parameters_backup.bson
Board architecture defaults: /etc/init.d/rc.board_arch_defaults
Board defaults: /etc/init.d/rc.board_defaults
Loading airframe: /etc/init.d/airframes/4001_quad_x
INFO [dataman] data manager file '/fs/microsd/dataman' size is 62560 bytes
Board sensors: /etc/init.d/rc.board_sensors
icm20602 #0 on SPI bus 1 rotation 8
ERROR [SPI_I2C] bmi088: no instance started (no device on bus?)
bmi085_accel #0 on SPI bus 5 rotation 8
bmi085_gyro #0 on SPI bus 5 rotation 8
icm20948 #0 on SPI bus 1 rotation 8
dps310 #0 on SPI bus 2
ekf2 [504:237]
Starting Main GPS on /dev/ttyS3
Starting MAVLink on /dev/ttyS1
INFO [mavlink] mode: Normal, data rate: 1200 B/s on /dev/ttyS1 @ 57600B
Board extras: /etc/init.d/rc.board_extras
INFO [logger] logger started (mode=all)
INFO [uavcan] Node ID 1, bitrate 1000000
NuttShell (NSH) NuttX-11.0.0
nsh> INFO [frsky_telemetry] Scanning timeout: exiting
nsh>
Screenshot / Media
No response
Flight Log
N/A
Software Version
HW arch: MRO_PIXRACERPRO
PX4 git-hash: a294e011ab1aac3fc3a2239c33eaa1326b914dab
PX4 version: 1.15.0 80 (17760384)
OS: NuttX
OS version: Release 11.0.0 (184549631)
OS git-hash: 5d74bc138955e6f010a38e0f87f34e9a9019aecc
Build datetime: Aug 8 2024 18:19:19
Build uri: localhost
Build variant: default
Toolchain: GNU GCC, 9.3.1 20200408 (release)
PX4GUID: 000600000000343439393432510e0036003e
MCU: STM32H7[4|5]xxx, rev. V
Flight controller
mRo Pixracer Pro
Vehicle type
None
How are the different components wired up (including port information)
Describe the bug
This board runs without issues with
stable
, somewhere in-between caused the following to malfunction:This is the output of
dmesg
forrelease/1.15
:To Reproduce
main
binary to a mRo Pixracer ProThe issue has been reproduced in other brand new mRo Pixracer Pro boards.
Expected behavior
Once placed on a leveled surface, the artificial horizon should not present an offset corresponding to the pitch/roll axis. Compass should be able to be recognized by PX4 and available for calibration.
This is the output of
dmesg
forv1.14.3
:Screenshot / Media
No response
Flight Log
N/A
Software Version
HW arch: MRO_PIXRACERPRO PX4 git-hash: a294e011ab1aac3fc3a2239c33eaa1326b914dab PX4 version: 1.15.0 80 (17760384) OS: NuttX OS version: Release 11.0.0 (184549631) OS git-hash: 5d74bc138955e6f010a38e0f87f34e9a9019aecc Build datetime: Aug 8 2024 18:19:19 Build uri: localhost Build variant: default Toolchain: GNU GCC, 9.3.1 20200408 (release) PX4GUID: 000600000000343439393432510e0036003e MCU: STM32H7[4|5]xxx, rev. V
Flight controller
mRo Pixracer Pro
Vehicle type
None
How are the different components wired up (including port information)
Board tested without other components.
Additional context
No response