`ap/geopose/filtered` doesn't reflect global position set in Gazebo world
Gazebo allows us to set the global position of a world via:
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>
<latitude_deg>37.412173071650805</latitude_deg>
<longitude_deg>-121.998878727967</longitude_deg>
<elevation>38</elevation>
</spherical_coordinates>
unfortunately this is not reflected by ap/geopose/filtered or MissionPlanner/QGroundControl but works on the topics from the navsat_sensor sensors.
This is because the Gazebo navsat sensor does not pass any information back to the FC. It's not really an issue with this repo, rather the data needs to be supplied to the FC from Gazebo, either through the ardupilot_gazebo repo ArduPilotPlugin or via another mechanism. My preferred approach would be to use DroneCAN following this prototype: https://discuss.ardupilot.org/t/sending-gazebo-sensor-data-to-ardupilot-using-dronecan/125730
Thanks for the quick reply. The integration with DroneCAN looks promising. I'll try this out with the GPS topic when I find the time.
Thanks for the quick reply. The integration with DroneCAN looks promising. I'll try this out with the GPS topic when I find the time.
There is some interest from other devs to use this for sensor integration as well - the approach needs a configuration framework, something like the yaml config used in gz_ros, to make it scalable. We may also need to review some of the DroneCAN messages, or augment the information coming from Gazebo.
As another workaround I found the home parameter inside the ardupilot_sitl/launch.py. When settings this as "home": "46.607213,14.278461,446.0,0" the pose of the GPS was initialized correctly but no matter what I inputed for the yaw the quad is always aligned to north:
Also disabling the compass didn't help resolve this:
@TannerGilbert - try the --custom-location="-35.28206849440639, 149.0059138453497, 581, 0" option when starting SITL. The last parameter is heading in degrees ("lat, lon, alt_amsl, hdg").
@srmainwaring thanks for the tip but I'm starting the simulation via sitl_dds_udp.launch.py which as far as I can see doesn't allow setting the custom-location but only the home parameter (https://github.com/ArduPilot/ardupilot/blob/master/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py#L588). My current launch setup:
sitl_dds = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[
FindPackageShare("ardupilot_sitl"),
"launch",
"sitl_dds_udp.launch.py",
]
),
]
),
launch_arguments={
"transport": "udp4",
"port": "2019",
"synthetic_clock": "True",
"wipe": "False",
"model": "json",
"speedup": "1",
"slave": "0",
"instance": "0",
"defaults": os.path.join(
pkg_custom_simulation,
"config",
"gazebo-iris.parm",
)
+ ","
+ os.path.join(
pkg_ardupilot_sitl,
"config",
"default_params",
"dds_udp.parm",
),
"sim_address": "127.0.0.1",
"master": "tcp:127.0.0.1:5760",
"sitl": "127.0.0.1:5501",
"home": "46.607213,14.278461,446.0,90",
"micro_ros_agent_ns": f"test123",
}.items(),
)