QGC Starts up showing a heading of north no mater the direction of compass
-
@Chase-Riley And when you say that you cannot go into position mode do you have a solid GPS lock?
-
@Chase-Riley In QGC can you open up mavlink inspector and take a look at the global position int message? How often is it coming in? Do all of the fields look like they are updating normally? Is hdg stuck at 0?
-
@Eric-Katzfey yes QGC artificial horizon and other telem reacts as it should. If I power up the air vehicle pointing south, east, or west it show that the heading is north. If I yaw the air vehicle the heading does change but it is incorrect because the system always starts at north.
I went a step further in testing and removed the GPS/Mag from the air vehicle. This allowed me to yaw the GPS/Mag independently from the air frame. When doing this QGC shows no change in heading. If I yaw the air vehicle while the GPS/Mag stays still the heading moves in QGC.
This makes it seem that QGC is getting heading info from the VOXL2 maybe IMU instead of the external GPS/Mag.
I have full GPS lock when trying to switch to position mode which makes me think that this heading issue could be why I can't switch into position.
I also have 5 total systems that are configured the same way. All 5 have this same heading issue.
-
@Eric-Katzfey I was able to look at
GPS_RAW_INT
in the mavlink inspector. Value seem to be updating at about 1Hz, however you are correct thatHDG_acc
us stuck at 0 no matter the heading of the Voxl or GPS/Mag. -
@Eric-Katzfey I was also able to flash 1 of my 5 systems to SDK 1.1.2 just to check to see if I have the same issue and it seems I do. I have included an error I found while running voxl-px4 on my SDK 1.1.2.
INFO [muorb] SLPI: >>> ICM42688P this: 3176eba0 INFO [muorb] SLPI: Ok executing command: icm42688p start -s INFO [uORB] Advertising remote topic qshell_retval INFO [muorb] SLPI: >>> ICM42688P this: 3176eba0 INFO [qshell] qshell return value timestamp: 46007098, local time: 46011498 INFO [muorb] SLPI: >>> ICM42688P this: 3176eba0 INFO [muorb] SLPI: Register interrupt b21d31a4 e6201b3c 3176eba0 INFO [uORB] Advertising remote topic sensor_gyro_fifo INFO [uORB] Advertising remote topic sensor_accel_fifo INFO [uORB] Advertising remote topic imu_server INFO [qshell] Send cmd: 'icp101xx start -I -b 5' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: icp101xx start -I -b 5 INFO [muorb] SLPI: arg0 = 'icp101xx' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-I' INFO [muorb] SLPI: arg3 = '-b' INFO [muorb] SLPI: arg4 = '5' INFO [muorb] SLPI: *** I2C Device ID 0xb76329 12018473 INFO [muorb] SLPI: icp101xx #0 on I2C bus 5 INFO [muorb] SLPI: address 0x63 INFO [muorb] SLPI: INFO [muorb] SLPI: Ok executing command: icp101xx start -I -b 5 INFO [qshell] qshell return value timestamp: 46049655, local time: 46051360 Looking for qmc5883l magnetometer INFO [qshell] Send cmd: 'qmc5883l start -R 10 -X -b 1' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: qmc5883l start -R 10 -X -b 1 INFO [muorb] SLPI: arg0 = 'qmc5883l' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-R' INFO [muorb] SLPI: arg3 = '10' INFO [muorb] SLPI: arg4 = '-X' INFO [muorb] SLPI: arg5 = '-b' INFO [muorb] SLPI: arg6 = '1' INFO [muorb] SLPI: *** I2C Device ID 0x80d09 527625 ERROR [muorb] SLPI: i2c probe failed INFO [muorb] SLPI: PX4_qshell: no instance started (no device on bus?) ERROR [muorb] SLPI: Failed to execute command: qmc5883l start -R 10 -X -b 1 INFO [qshell] cmd returned with: -1 INFO [qshell] qshell return value timestamp: 46090352, local time: 46091734 ERROR [qshell] Command failed Looking for ist8310 magnetometer INFO [muorb] SLPI: >>> ICM42688P this: 3176eba0 INFO [qshell] Send cmd: 'ist8310 start -R 10 -X -b 1' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: ist8310 start -R 10 -X -b 1 INFO [muorb] SLPI: arg0 = 'ist8310' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-R' INFO [muorb] SLPI: arg3 = '10' INFO [muorb] SLPI: arg4 = '-X' INFO [muorb] SLPI: arg5 = '-b' INFO [muorb] SLPI: arg6 = '1' INFO [muorb] SLPI: *** I2C Device ID 0x60e09 396809 INFO [muorb] SLPI: ist8310 #0 on I2C bus 1 INFO [muorb] SLPI: (external) INFO [muorb] SLPI: address 0xE INFO [muorb] SLPI: rotation 10 INFO [muorb] SLPI: INFO [muorb] SLPI: Ok executing command: ist8310 start -R 10 -X -b 1 INFO [qshell] qshell return value timestamp: 46128693, local time: 46130008 INFO [qshell] Send cmd: 'gps start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: gps start INFO [muorb] SLPI: arg0 = 'gps' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Creating pthread gps INFO [muorb] SLPI: Successfully created px4 task PX4_gps with tid 2097647 INFO [muorb] SLPI: Ok executing command: gps start INFO [qshell] qshell return value timestamp: 46153157, local time: 46155078 Looking for ncp5623c RGB LED INFO [qshell] Send cmd: 'rgbled_ncp5623c start -X -b 1 -f 400 -a 56' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic
-
@Chase-Riley It makes me believe that one of the rotations somewhere is not set correctly. What is SENS_BOARD_ROT set to? I guess we can just trace the topic messages through the system to see where it is getting confused. So you already did listener sensor_mag and you can see it publishing and the values updating regularly when you move the unit around? That topic goes to the sensors module that then publishes the vehicle_magnetometer topic. Can you do a listener on that to make sure it looks like it is working?
-
@Chase-Riley What happens when you try to do a compass calibration?
-
@Chase-Riley That error is normal. It tries to start both mag drivers assuming that one will fail.
-
@Chase-Riley Also, when arming is failing in position mode you can do a listener on the failsafe_flags topic to see what flags are set.
-
@Eric-Katzfey running
px4-listener sensor_mag
shows the mag data and it changes as I move the GPS/Mag around. So that is behaving how I would expect it toSENS_BOARD_ROT
is set to YAW 180. This is due to the VOXL2 being mounted 180 degrees rotated in the air frame.Everything seems to go well through an compass calibration. We have done quite a few while troubleshooting this.
I will take a look at the failsafes when I try to go into position mode, however at this point I think the heading needs to be resolved first either way. Am I correct to think that when rotating the GPS/Mag separate from the VOXL2 I should see a heading change based on the direction of the GPS/Mag? In this case I only see the heading change when rotating the VOXL2 (Which to my knowledge has no Mag on board).
-
@Chase-Riley Instead of setting SENS_BOARD_ROT you can set the rotation on the IMU driver to
-R 4
. But don't do both. I would try setting SENS_BOARD_ROT to 0 and keeping the-R 4
on the IMU driver start and see if that makes any difference. Also, do thelistener vehicle_magnetometer
to see if it is updating nicely likelistener sensor_mag
does. -
@Chase-Riley Is there any way that you can orient the board exactly as we have it in one of our drones (Sentinel, Starling) and use our parameter set and see if it works fine then?
-
@Eric-Katzfey I set
SENS_BOARD_ROT
to No rotation and made the change to the IMU driver as you mentioned and had the same results still always points north on startup.px4-listener vehicle_magnetometer
updates nicely as just likepx4-listener sensor_mag
.I was able to flash the sentinel params on to the board and was able to match the orientation of the Sentinel and had the same results. I made sure to change the IMU driver back to original before this test.
-
@Eric-Katzfey I went back in this morning and flashed the
ci_sentinel-params
which seems to be a entire param set and was able to get it working. Now I need to change the VOXL2 orientation. Would you recomend doing this through QGC or thevoxl-px4-start
? I am unsure which parameter caused it to start to work. Any insight would be appreciated so that I can make that change in my other systems with out having to change a bunch of params. -
@Eric-Katzfey I pulled the params from the system I have working and one of the systems that is having the Mag problem. Weirdly enough there is only 9 differences. I have listed them below. They all seem to be calibration differences if I understand correctly.
CAL_ACC0_XOFF
CAL_ACC0_YOFF
CAL_ACC0_ZOFFCAL_GYRO0_XOFF
CAL_GYRO0_YOFF
CAL_GYRO0_ZOFFCAL_MAG0_XSCALE
CAL_MAG0_YSCALE
CAL_MAG0_ZSCALE -
@Chase-Riley Huh, that's very interesting. I'm guessing that if the rotation isn't set properly and a calibration is done then those calibration parameters will be incorrect such that even when all rotations are specified correctly those old calibration values will mess everything up. So I guess that each time any rotation parameter or option is changed you need to go and recalibrate everything. For your case it seems like you should leave everything the same as Sentinel except change the rotation of the IMU driver in voxl-px4-start to
-R 4
and then recalibrate everything. -
@Eric-Katzfey It is interesting. I was able to get this working on SDK 1.1.2. This morning I tried to follow the same procedure with one of my SDK 1.0 systems and have had no luck. I reflashed the sentinel params and changed the rotations back to factory just like I did on the SDK 1.1.2 system and had no luck. I am guessing next steps at this point will be to upgrade my SDK 1.0 system to SDK 1.1.2 and see if the issue is solved.
-
@Chase-Riley Definitely would recommend being on 1.1.2 at this point.