I have a depth camera system on an nvidia jetson which is sending the mavlink VISION_POSITION_ESTIMATE message over serial 3 to my flight controller. In mission planner I can see the message successfully arrive/update in the mavlink inspector (right of the image) under Vehicle 1 → Comp 0 MAV_COMP_ID_ALL.
The X Y Z values are correct but for some reason I keep getting the PreArm: Need Position Estimate error in Loiter mode.
In the messages console in mission planner I continually get the messages:
19/03/2025 15:58:12 : EKF3 IMU0 initial pos NED = (x),(y),(z) (m)
19/03/2025 15:58:12 : EKF3 IMU0 is using external nav data
19/03/2025 15:58:12 : EKF3 IMU0 stopped aiding
where (x), (y), (z) are the values coming from VISION_POSITION_ESTIMATE as mentioned. As it is also reading the right xyz values here I am trying to understand why this prearm error keeps appearing.
My params are as follows:
VISO_TYPE = 2 (IntelT265) (I’ve also tried option 1 MAVLink)
VISO_DELAY_MS = 100ms (The jetson sends it around 10-15hz so this should be good)
Could it be any of the following.
1- Im only sending position estimate and not velocity estimate. Does it need this too or not? (i assume if it did then it instead “PreArm: Need Velocity Estimate” which it doesnt but i could be wrong)
2- Although I can see VISION_POSITION_ESTIMATE on mavlink inspector. Is the Comp 0 right or wrong. Id assume it isnt as the EKF3 is printing the correct xyz values in the messages window
I’m far from an expert for Vision_poition_Estimation but did you set the EKF origin at the beginning?
To me it seems like you didn’t because the position on the map is shown as 0 and 0, but the map is clearly pointing to somewhere else…
Ive now set EKF origin to just outside London (where I’m based). But as Im not using GPS but a visual odom system, I dont see how this would help. Regardless, I did it but it didnt fix it.
Okay, I’m pretty sure it’s necessary, but I can’t explain you why…
I just tested it with this code a few weeks back and know that this worked (I could see the drone move in MissionPlanner:
from pymavlink import mavutil
import time
lat = 12345
lon = 12345
alt = 0
vehicle = mavutil.mavlink_connection(‘udpin:localhost:14553’)
boot_time = time.time()
print(‘Waiting for heartbeat’)
vehicle.wait_heartbeat()
print(“Heartbeat from system (system %u component %u)” % (vehicle.target_system, vehicle.target_component))
vehicle.mav.set_gps_global_origin_send(1, lat, lon, alt)
vehicle.mav.set_home_position_send(1, lat, lon, alt, 0, 0, 0, [1, 0, 0, 0], 0, 0, 1)
x = 0.0
y=0.0
while(1):
vehicle.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS, mavutil.mavlink.MAV_AUTOPILOT_INVALID, 0, 0, 0)
time.sleep(1)
vehicle.mav.vision_position_estimate_send(
int(time.time()*1000.0), # us Timestamp (UNIX time or time since system boot)
float(x), # Global X position
float(y), # Global Y position
float(0.0), # Global Z position
float(0.0), # Roll angle
float(0.0), # Pitch angle
float(0.0), # Yaw angle
[float(0) for _ in range(21)], # Row-major representation of pose 6x6 cross-covariance matrix
int(0) # Estimate reset counter. Increment every time pose estimate jumps.
)
x +=1
y -= 1
Ok ive added to my python script (running on the jetson that sends to the FC) what you’ve instructed.
vehicle.mav.set_gps_global_origin_send(1, lat, lon, alt)
vehicle.mav.set_home_position_send(1, lat, lon, alt, 0, 0, 0, [1, 0, 0, 0], 0, 0, 1)
As you can see in the mavlink inspector in the image, the lon and lat values (under the global_position_int param) are 12345 meaning the message was sent through successfully…
But I’m still getting the same error (preArm Need position estimation)
Can you just try my script (with updated connection string of course)?
What I just spotted is that it seems like Global_Origin is coming with 2Hz, but sending it once should be enough… But I can’t imagine that this is the problem…
It was to do with the EKF failsafe. There was incorrect position values coming in triggering the failsafe. I corrected directions of the xyz values coming in so that they werent triggering the failsafe and it worked though ive got much tuning to do.
I’m currently facing a similar problem. Could you tell me which direction to go in order to get rid of the Need Position Estimate message? All documentation settings have been made, messages are being received, and the home position has been set.
This page shows how to setup ROS and Hector SLAM using an RPLidarA2 lidar to provided a local position estimate for ArduPilot so that it can operate without a GPS.