Yaw error in hardware test #158
-
Hello, We have recently started to do hardware tests with a T650 UAV. We started to test the control of the UAV for small trajectory steps of 1m in x, then y and then z by using default gains. It was able to work well. Later we changed to higher gains. With these new gains, the UAV starts to rotate close to 160° at the moment we ask it to go to the start of its trajectory. The step asked at that moment is very small (around 20-30 cm in x,y,z) as the UAV is close to the start of its trajectory already. No error is printed in the controller tab, except " Activating emergency land: Yaw error 160/90". We are wondering why an increase of the gains produces a yaw rotation when asking to go to the trajectory start. No errors or warnings that could help us understand what happens are printed. Would you have any clue what the issue could be? |
Beta Was this translation helpful? Give feedback.
Replies: 5 comments 3 replies
-
Hey, this is really strange. Could you provide a rosbag? Alternatively, could you provide the tmux script logs, which should be logged automatically by our tmux sessions? |
Beta Was this translation helpful? Give feedback.
-
Hello @klaxalk, 1_Roscore.log |
Beta Was this translation helpful? Give feedback.
-
Hi @klaxalk, Today I did hardware tests again. As discussed above, I calibrated again the pixhawk of the UAV to hopefully resolve the issue. Unfortunately, it was not resolved.
Here are the plotted result of the last test: On the left, it shows the x,y,z position, the thrust and the angular body rates. On the right is the mavros/global_position/compass_hdg. It is at the moment of the jump in the compass heading measurement that the desired angular body rate is saturating and that the UAV starts to rotate. The error in the control.log is also giving an yaw error of 125, which is the value of the jump in the compass heading measurement. We now know that 2 different UAVs that were calibrated today on site have the same problem. My two main questions are:
Thoughts and information that could be useful to understand the problem: a. The firmware on both pixhawks is 1.13.2. We upgraded from 1.11.2 @spurnvoj said that the old firmware is not compatible with the latest CTU system (#149 (reply in thread)). Is firmware 1.13.2 the good one and compatible with the CTU system of February 2023 ? b. Could it be due to an interference from cables on the UAV itself ? Altought, cabling on the T650 seems to be similar to the one on the f450 where it worked fine. c. Before the first UAV had this issue, tests worked all right. Later, I recalibrated the sensors and ESCs for the first time on site. It is possibly just after this that the issue arose. What could there be wrong with the calibration on site? There is no high-voltage power line. Only some screens, computers and an extension cord. I calibrated the compass, the gyroscope, the accelerometer and the horizon level. For the compass calibration, I rotated the UAV CCW around its center of mass, with the same initial orientation as in the tests. d. There are several solar panels at around 20 m from the take-off zone and from where the calibration was done. Is it possible this would give an issue? e. To be sure the pixhawk doesn't move during tests, we added little strips of duct tape on the sides of the pixhawk. Could this be a problem? f. Are we sure it is only a problem of compass measurement? The cause of the problem is clearly the jump in heading measurement, but it is weird that it happens just during changes of reference steps and not at any moment. Also, the test with less aggressive gains seems to be more resilient to this issue. g. On our T650 UAVs, we have a pixhawk 4, a GPS module (Pixhawk 4 GPS module: which has an integrated compass) and a RTK system. Is the magnetometer used by the pixhawk the one in the pixhawk itself or the one of the GPS module? If it is the one of the pixhawk, using the one of the GPS could solve interference problems. Was this already used by CTU ? Here is wetransfer link for a ZIP file containing the Rosbag file and log files of each test. (numbered from 1 to 4 like explained above) and a smaller ZIP only containing the data of the last test: Thanks a lot for for all your help. Have a nice day, Martin |
Beta Was this translation helpful? Give feedback.
-
The issue has been resolved by disabling the internal compass in QGroundControl. (CAL_MAG0_PRIO on disabled) and using only the external compass in the GPS module. (CAL_MAG1_PRIO on high). The default configuartion were CAL_MAG0_PRIO = medium and CAL_MAG1_PRIO on high. |
Beta Was this translation helpful? Give feedback.
-
Confirming the solution. @stibipet has observed the same issue and solved it the same way by disabling the internal compass. |
Beta Was this translation helpful? Give feedback.
The issue has been resolved by disabling the internal compass in QGroundControl. (CAL_MAG0_PRIO on disabled) and using only the external compass in the GPS module. (CAL_MAG1_PRIO on high). The default configuartion were CAL_MAG0_PRIO = medium and CAL_MAG1_PRIO on high.