Agressive Takeoff and lateral drift in OFFBOARD mode with vision pose

Hi PX4 Community,

I’m currently working on an autonomous drone project without GPS. In OFFBOARD mode using MAVROS i am able to fed the current position to the pixhawk through the topic mavros/vision_pose/pose and the setpoint through the topic mavros/setpoint_position/local and i verified that the data in QGC is matching (showing in NED form correctly ) with the data whatever i am sending using MAVROS (sending the position and setpoint data in ENU form ) but When flying in OFFBOARD mode, the drone becomes aggressive and unstable, especially in lateral motion. Despite commanding a stable hover at (0, 0, 1), it pitches/rolls and drifts sideways, instead of maintaining a steady position. What could be causing this lateral drift and instability?Are there specific parameters or configurations I should review to improve position stability?
How can I ensure smoother and more reliable OFFBOARD control in this GPS-denied setup?

Any insights or suggestions would be greatly appreciated. Thank you in advance!
Components used:
Flight controller:Pixhawk 6X
Firmware:PX4 V1.15
Frame:X500 frame kit
Companion computer:Jetson nano
Control mode:OFFBOARD mode
Sensors:YDLidar G2(2D LIDAR) and TFmini single point Lidar.

hard to tell without a log example.
I would check variances and innovations of the visual info on the px4 side, they should be in topics:
estimator_aid_src_ev_pos
estimator_aid_src_ev_vel
need to make sure these are in the logs, so make sure to set correct SDLOG_PROFILE.

Thanks for your response!

As per your suggestion, I enabled the necessary logging for estimator data by setting the SDLOG_PROFILE parameter to 131 to include EKF2 replay ,computer vision and avoidance and additional estimator information. I then conducted a static test (without propellers) in OFFBOARD mode. Here’s what I did:

  • Duration: 30 seconds total
  • I started publishing position and setpoint topics via MAVROS.
  • For the first 15 seconds, the drone was active (motors spinning).
  • After that, I pressed Ctrl+C to stop the MAVROS node, and within ~15 seconds the motors stopped.
    Here is the Flight Review log link for the session:
    https://logs.px4.io/plot_app?log=e2a0ca9b-38e9-46e2-a0c2-501706607c93

Please let me know if this log captures the required estimator_aid_src_ev_pos and estimator_aid_src_ev_vel data correctly or if I should modify the test procedure.
Looking forward to your insights to help debug the lateral drift and improve OFFBOARD stability in this GPS-denied setup.

Thanks again!

  1. the aid info topics are commented out in your version, better to add them:
    PX4-Autopilot/src/modules/logger/logged_topics.cpp at 99c40407ffd7ac184e2d7b4b293f36f10fe561ef · PX4/PX4-Autopilot · GitHub

  2. your EKF2_EV_CTRL is set to 15, to expect all EV data:

  • 0: Horizontal position
  • 1: Vertical position
  • 2: 3D velocity
  • 3: Yaw
    but in the vehicle_odometry topic looks like only position is sent, no velocity. better check only aid data that you send
  1. better disable multi-EKF, now you have 3, it’s harder analyze logs this way
    Using PX4's Navigation Filter (EKF2) | PX4 Guide (main)