mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
896 stars 993 forks source link

/mavros/global_position/local not always start at 0,0,0 #1213

Closed elgarbe closed 5 years ago

elgarbe commented 5 years ago

Hi, is global_position/local an odomotry topic or is it a ECEF position of the vehicle? Some time that topic start from 0,0,0 like an odomety, but some times is start at ECEF coordinates of my vheicle. I'm using px4 in SITL. What about /local_position/pose? what is the frame of this message?


Issue details

Please describe the problem, or desired feature

MAVROS version and platform

Mavros: ?0.18.4? ROS: ?Kinetic? Ubuntu: ?16.04?

Autopilot type and version

[ ] ArduPilot [ ] PX4

Version: ?3.7.1?

Node logs

copy output of mavros_node. Usually console where you run roslaunch

Diagnostics

place here result of:
rostopic echo -n1 /diagnostics

Check ID

rosrun mavros checkid
TSC21 commented 5 years ago

Hi, is global_position/local an odomotry topic or is it a ECEF position of the vehicle?

That topic is an odometry of the vehicle but computed from an ECEF origin, so the position is in the ECEF cartesian local frame.

What about /local_position/pose? what is the frame of this message?

It's the local NED frame.

ericjohnson97 commented 5 years ago

I too have noticed that global_position/local topic sometimes starts at 0 0 0, and some times starts as ECEF. It seems very random to me which frame global_position/local will be as I will launch my gazebo + Arducopter SITL setup and get the 0 0 0 the first time, and the ECEF version the next. Its super strange to me, as I have been testing this for the last few hours and the reference frame can change with no modifications made to my setup. I would appreciate any clues as to why this would happen. Thanks in advance!

TSC21 commented 5 years ago

@ericjohnson97 please provide the steps to reproduce it and an example output of what you are seeing so this can be debugged and fixed. Thank you

ericjohnson97 commented 5 years ago

give me a little bit. I still can't reliably produce either scenario. I am going to continue to try and track this one down. I will let you know what I find. Best!

elgarbe commented 5 years ago

I couldn't find a way to get always 0,0,0 or always ECEF. I launch iris/mavros and echo the message, if it is wrong I kill simulation and start over. Some times it works for several hours, but sometimes it fails a couple of times. Let me know if you found a solution.

ericjohnson97 commented 5 years ago

ah ha! I have found the problem. So the global position/local topic will publish position messages with an incorrect origin, when it has no GPS fix. You can cause this this state occur in simulation by launching your flight stack sitl and then quickly launching the mavros node. what happens is that it takes around 10 - 20 seconds for arducopter to boot and get a simulated gps fix. In this time, mavros can initialize the global position plugin without a gps fix. Even when arducopter obtains a GPS fix the variable ecef_orgin in global_position.cpp will not reset to the correct origin position. By default the variable will fill to x 6378154.163000 y 0.000000 z 0.000000, which is just the radius of the earth. So then when the drone gets a position fix it is very far away from its mavros' default set "origin".

My Testing Procedures

I am using Gazebo + ardupilot plugin + ardupilot sitl + mavros

my gazebo world and apm launch file are here https://github.com/Intelligent-Quads/iq_sim

Make Error Occur

1.) launch world

roslaunch iq_sim hills.launch

2.) launch ardupilot sitl

cd ~/ardupilot/ArduCopter/ && sim_vehicle.py -v ArduCopter -f gazebo-iris --console

3.) quickly launch mavros

roslaunch iq_sim apm.launch

the easy fix is to wait until the flight stack gets a gps fix and then launch mavros, but that is slightly annoying and it might be nice to implement a bit of logic to reset the origin once gps fix is obtained. Plus this way it is much more forgiving to new developers. @TSC21 Let me know if you think there should be a software fix to handle this. If so, I would be willing to write it.

TSC21 commented 5 years ago

@ericjohnson97 thanks for your finding. Please if you are willing to fix it, do it and I will gladly review it. Thank you!

ericjohnson97 commented 5 years ago

perfect! I think the fix was a simple as adding a small check for the a good gps fix before setting the origin. Let me know if there are any issues with this I did not foresee. Best!

https://github.com/mavlink/mavros/pull/1269

sagarwal-atg commented 5 years ago

I am not getting /mavros/global_position/local in mavros. Any idea ? I am not seeing that topic at all. Do I need to set anything in the qgroundcontrol?

elgarbe commented 5 years ago

rosrun mavros mavsys rate --all 10

TSC21 commented 5 years ago

This is fixed already. Closing