ZJU-FAST-Lab / ego-planner

GNU General Public License v3.0
1.29k stars 268 forks source link

PX4 Cntrl changes #68

Closed EhrazImam closed 11 months ago

EhrazImam commented 1 year ago

@bigsuperZZZX As you can see over here https://github.com/ZJU-FAST-Lab/Fast-Drone-250/issues/33#issuecomment-1331634422 I want to know if we are using VIO then why we need mavros/imu/data as far i know that mavros/imu/data gives us acc,gyro and orientation and where as /mavros/imu/data_raw we only get acc and gyro. If you are flying over VIO, why do you need the magnetometer? Thankyou

bigsuperZZZX commented 1 year ago

The VIO pose is computed relative to the world frame where the x-axis points to the forward direction when you start VINS. However, the PX4 FCU update orientation is based on its own world frame. These two world frames are not aligned, especially in the yaw direction. So we have to subscribe the mavros/imu/data to acquire the yaw difference between the world frames of VINS and the FCU, so that we can convert the quaternion command computed in the VINS world frame to the FCU world frame.

FPSychotic commented 1 year ago

Can you point that part in the code, where is the quaternion conversion, I guess it is from NED to ENU , would be nice find it in the code if possible

bigsuperZZZX commented 1 year ago

https://github.com/ZJU-FAST-Lab/Fast-Drone-250/blob/8ff64274b161bb829653faf5946656658e7e2c9f/src/realflight_modules/px4ctrl/src/controller.cpp#L51

EhrazImam commented 11 months ago

@bigsuperZZZX How can we solve this if i dont want to pass compass data and just want it to run over /mavros/imu/data_raw and what will be the issue.

As drone is equipped with a single magnetometer housed inside the Pixhawk 4 mini. However, this magnetometer's reliability is compromised due to its proximity to numerous wires, making it susceptible to interference from current magnetic fields. The FCU orientation heavily relies on the data provided by both the inertial measurement unit (IMU) and the magnetometer.

The indoor environment, often characterized by various electronic devices, introduces further challenges, potentially leading to magnetometer failure. Consequently, the FCU's orientation, particularly the estimation of yaw, may suffer from instability and fluctuation issues.

As i am planning to use px4 ctrl and vio in high magnetic field so it will deflect magnetometer. What will be the possible solution.

bigsuperZZZX commented 11 months ago

You can switch the state estimatior of PX4 from EKF to Q Estimator as this estimator can ignore the magnetometer readings. To completely turn off the compass, set SYS_HAS_MAG to 0.

EhrazImam commented 11 months ago

Thankyou @bigsuperZZZX for you reply.

This means i can take flight without having compass but as we are subscribing mavros/imu/data which is fusion of magnetometer and imu how i an going to subscribe if i am going to turn it off and as you mentioned previously https://github.com/ZJU-FAST-Lab/Fast-Drone-250/blob/8ff64274b161bb829653faf5946656658e7e2c9f/src/realflight_modules/px4ctrl/src/controller.cpp#L51 this line use orientation of imu so isn’t its taking magnetometer orientation

bigsuperZZZX commented 11 months ago

Magnetometer is not the necessarity for mavros/imu/data.

EhrazImam commented 11 months ago

Thankyou @bigsuperZZZX

bzw-uestc commented 7 months ago

@EhrazImam I also encountered the same problem. After pixhawk 6c is configured as a complementary filter estimator, /mavros/imu/data cannot be obtained. How did you solve it?

bigsuperZZZX commented 2 months ago

@bzw-uestc you need to let pixhawk 6c transmit the orientation mavlink message of the same frequency to the IMU message, then you can get /mavros/imu/data back. Complementary filter estimator is not the problem.