I wrote a new driver for an external IMU and I am publishing over uORB the accel, gyro, magnetometer and baro readings. I noticed in QGroundControl that the changes in yaw, pitch, roll are happening very very slowly. Unsafe to fly.
I plotted the attached graph for readings of magnetometer and the output of EKF2 quaternions (from log_…_vehicle_attitude_0.csv) when I moved the IMU on the table so that only the yaw change. As you can see, the delay between driver output and estimated quaternions take a very long time.
Platform: PX4v5 with IMU read over serial. uOrb messages posted at 200 Hz for all components (accel, gyro, mag and baro).
Questions: Any idea what can be the root cause of this and how can it be fixed ?
Any hints about where to look for the problem and how to find a solution will be highly appreciated.
Hi bresch,
Thank you for your suggestion.
I run the script and I got the attached pdf.
Not sure that this flags the problem, but I see in diagram Magnetic Heading Innovation (page 6) that there seems to be some cut-off at the max value of 0.781.
What can be the meaning of this ? Is there some upper limit that is reached ?
I started to suspect that there may be some issues with the calibration.
Can somebody point me to the documentation for them ? More precisely:
How do I choose the device id that I sent in uORB messages ?
I randomly choose 77 for all the id’s (accel, gyro, mag and baro) implemented in my driver.
Is there any rules I have to follow? Is a relationship between the devId reported in uORB and the name of the device (like /dev/accel0 as opposed to /dev/accel77).?
I added some printout in commander. It attempts to open only one magnetometer (/dev/mag0 ) and it gets back my id 77. Good ! This is what I expected.
However, later in the calibration process in function mag_calibrate_all() at the line:
orb_mag_count=orb_group_count(ORB_ID(sensor_mag));
the count is returned as 2 (despite the fact that it never opened any other /dev/magX other then 0 - which is mine).
Then later in the loop it fails to get anything from a second magnetometer (since there is no other running) and the calibration fail for the nonexistent mag 1.
I even run uorb without my driver running and no sensor_mag message is ever published.
So, from where the second magnetometer instance came from, and how can I fix it.
Do you believe that may be something wrong with orb_group_count ?
Hi @MTM wanted to check how did you integrate your new uORB topic with EKF2?
@bresch is it possible to define a new uORB topic like vehicle_imu (say vehicle_imu_ai) and pass that into EKF2 without breaking other parts like mavros/imu/data?
I simply want my EKF2 to process IMU data from vehicle_imu_ai (which sources from /mavros/imu/data and performs a filtering) instead of using the SITL vehicle_imu data
@bresch My goal is to get /mavros/imu/data → AI Model → UDP → New uORB topic → EKF2 → AI-corrected State Estimation.
As of now, I’m able to send my data to the new uORB topic. But EKF2 by default relies on vehicle_imu, the minute I try to switch from that to my new uORB topic, mavros/imu/data stops publishing and that kills my input to the AI Model.
When I say mavros/imu/data stops publishing, I mean - its frequency drops to hearbeats or “no new messages”. While on the PX4 terminal, I keep getting “poll timeout 0, 22” errors.
Interestingly, the minute I switch back to vehice_imu, everything falls back in place and starts working properly. I’m making this switch based on a simple custom parameter I defined (0 for Normal-mode, 1 for AI-mode)
My only question now is - How exactly to register/subscribe to vehicle_imu/New uORB topic so as to keep receiving SITL imu data and pass that to my AI model without killing /mavros/imu/data. I’m also fine with receiving my imu data in some other way apart from mavros (as long as I can receive it).