Complete Gazebo 11 → GZ Harmonic conversion for NPS simulator (#3607)

* Initial plan

* Update SDF models for GZ Harmonic compatibility

- Update SDF version from 1.4 to 1.9 in all model files
- Remove deprecated velocity_decay blocks

Co-authored-by: Copilot <223556219+Copilot@users.noreply.github.com>

* Fix GZ Harmonic integration: rewrite nps_fdm_gazebo.cpp with proper System plugin, convert world files to SDF, update launchers

Co-authored-by: dewagter <490108+dewagter@users.noreply.github.com>

* Address review feedback: guard against division by zero in yaw_coef, add heading_deg comments

Co-authored-by: dewagter <490108+dewagter@users.noreply.github.com>

* Add sdformat14 to explicit pkg-config dependencies

Co-authored-by: dewagter <490108+dewagter@users.noreply.github.com>

---------

Co-authored-by: copilot-swe-agent[bot] <198982749+Copilot@users.noreply.github.com>
Co-authored-by: Copilot <223556219+Copilot@users.noreply.github.com>
Co-authored-by: dewagter <490108+dewagter@users.noreply.github.com>
This commit is contained in:
Copilot
2026-02-19 16:42:00 +01:00
committed by Christophe De Wagter
parent cff6953887
commit 71a18fb2af
17 changed files with 487 additions and 326 deletions
+3 -3
View File
@@ -3,11 +3,11 @@
<module name="fdm_gazebo" dir="fdm">
<doc>
<description>
Gazebo backend for NPS simulator
Gazebo Harmonic backend for NPS simulator
NPS doc: http://wiki.paparazziuav.org/wiki/NPS
Usage:
1. Make sure gazebo 9 is installed. (sudo apt-get install gazebo9 libgazebo9-dev)
1. Make sure Gazebo Harmonic is installed. (sudo apt-get install gz-harmonic)
2. Prepare the Gazebo world and model:
1. Prepare the UAV model (see conf/simulator/gazebo/models/ardrone/):
- Place the aircraft model in the conf/simulator/gazebo/models/
@@ -135,7 +135,7 @@
<header/>
<makefile target="nps">
<raw>
GZ_COMPONENTS = gz-sim8 gz-transport13 gz-msgs10 gz-math7 gz-sensors8
GZ_COMPONENTS = gz-sim8 gz-transport13 gz-msgs10 gz-math7 gz-sensors8 sdformat14
nps.CXXFLAGS += $(shell pkg-config --cflags $(GZ_COMPONENTS)) -fPIC
nps.LDFLAGS += $(shell pkg-config --libs $(GZ_COMPONENTS))
@@ -1,12 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="ardrone">
<pose>0 0 .1 0 0 0</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial><!-- Converted to SI from Paparazzi's ARDrone model for JSBsim -->
+1 -5
View File
@@ -1,13 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="bebop">
<pose>0 0 .1 0 0 1.57</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial>
<mass>0.536</mass><!-- With bumpers. Tuned for correct nominal hover thrust, mass is higher than in real life (~0.40kg) -->
<inertia>
@@ -1,12 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="bebop2">
<pose>0 0 .1 0 0 0</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial>
<mass>0.536</mass>
@@ -1,12 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="bebop2_with_slamdunk">
<pose>0 0 .1 0 0 0</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial>
<mass>0.536</mass>
@@ -1,12 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="bebop_w_stereo_cams">
<pose>0 0 .1 0 0 1.57</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial>
<mass>0.536</mass><!-- With bumpers. Tuned for correct nominal hover thrust, mass is higher than in real life (~0.40kg) -->
@@ -1,5 +1,5 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="range_sensors">
<link name="base">
<inertial>
@@ -1,12 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="simple_quad">
<pose>0 0 .1 0 0 0</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial><!-- Converted to SI from Paparazzi's ARDrone model for JSBsim -->
@@ -1,12 +1,9 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="simple_x_quad">
<pose>0 0 .1 0 0 0</pose>
<link name="chassis">
<velocity_decay>
<linear>0.001</linear>
</velocity_decay>
<inertial><!-- Converted to SI from Paparazzi's ARDrone model for JSBsim -->
@@ -1,5 +1,5 @@
<?xml version='1.0'?>
<sdf version='1.4'>
<sdf version='1.9'>
<model name="slamdunk">
<link name="slamdunk_link">
<visual name="visual">
@@ -0,0 +1,82 @@
<?xml version='1.0'?>
<sdf version="1.9">
<world name="cyberzoo">
<physics type="ode">
<max_step_size>0.001</max_step_size>
<real_time_update_rate>0</real_time_update_rate><!-- Handled by Paparazzi! -->
</physics>
<!-- Without lighting -->
<scene>
<ambient>0.9 0.9 0.9 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>false</shadows>
</scene>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>51.9906361</latitude_deg>
<longitude_deg>4.3767874</longitude_deg>
<elevation>45.110</elevation>
<heading_deg>0</heading_deg><!-- GZ Harmonic fixed the WSU/ENU coordinate bug; no longer need heading=180 workaround -->
</spherical_coordinates>
<model name="ground_plane">
<static>true</static>
<pose>0 0 -0.02 0 0 0.454</pose>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
</material>
</visual>
</link>
</model>
<include>
<uri>model://cyberzoo</uri>
<pose>0 0 0 0 0 0.454</pose>
</include>
<include>
<uri>model://orange_pole</uri>
<name>orange_pole1</name>
<pose>-1.8 -3.4 0 0 0 0</pose>
</include>
<include>
<uri>model://orange_pole</uri>
<name>orange_pole2</name>
<pose>-1.8 0.5 0 0 0 0</pose>
</include>
<include>
<uri>model://orange_pole</uri>
<name>orange_pole3</name>
<pose>0.6 0.7 0 0 0 0</pose>
</include>
<include>
<uri>model://orange_pole</uri>
<name>orange_pole4</name>
<pose>1.5 -2.5 0 0 0 0</pose>
</include>
<include>
<uri>model://orange_pole</uri>
<name>orange_pole5</name>
<pose>2.8 2.5 0 0 0 0</pose>
</include>
</world>
</sdf>
+30 -8
View File
@@ -1,5 +1,5 @@
<?xml version='1.0'?>
<sdf version="1.6">
<sdf version="1.9">
<world name="empty">
<physics type="ode">
<max_step_size>0.001</max_step_size>
@@ -8,11 +8,11 @@
<scene>
<ambient>1 1 1 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>0</shadows>
<shadows>false</shadows>
</scene>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose frame=''>0 0 10 0 -0 0</pose>
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<attenuation>
@@ -28,11 +28,33 @@
<latitude_deg>51.9906340</latitude_deg>
<longitude_deg>4.3767889</longitude_deg>
<elevation>45.110</elevation>
<heading_deg>180</heading_deg><!-- Temporary fix for issue https://bitbucket.org/osrf/gazebo/issues/2022/default-sphericalcoordinates-frame-should -->
<heading_deg>0</heading_deg><!-- GZ Harmonic fixed the WSU/ENU coordinate bug; no longer need heading=180 workaround -->
</spherical_coordinates>
<include>
<uri>model://ground_plane</uri>
</include>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
</material>
</visual>
</link>
</model>
</world>
</sdf>
+16 -70
View File
@@ -1,12 +1,8 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from imav_indoor.world.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<sdf version="1.6">
<sdf version="1.9">
<world name="square_world">
<light name="sun" type="directional">
<cast_shadows>1</cast_shadows>
<cast_shadows>true</cast_shadows>
<pose>0 10 0 0 0 -1.57079632679</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
@@ -23,32 +19,20 @@
<latitude_deg>51.9906340</latitude_deg>
<longitude_deg>4.3767889</longitude_deg>
<elevation>45.110</elevation>
<heading_deg>180</heading_deg><!-- Temporary fix for issue https://bitbucket.org/osrf/gazebo/issues/2022/default-sphericalcoordinates-frame-should -->
<heading_deg>0</heading_deg><!-- GZ Harmonic fixed the WSU/ENU coordinate bug; no longer need heading=180 workaround -->
</spherical_coordinates>
<physics type="ode">
<max_step_size>0.001</max_step_size>
<real_time_update_rate>0</real_time_update_rate><!-- Handled by Paparazzi! -->
</physics>
<gravity>0 0 -9.8</gravity>
<gui fullscreen="0">
<camera name="user_camera">
<pose>1.49016 -3.72367 3.62379 -2.88294e-17 0.273797 1.4042</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>0</shadows>
<grid>0</grid>
<shadows>false</shadows>
</scene>
<model name="floor">
<static>1</static>
<static>true</static>
<pose>0.0 0.0 0 0 0 0</pose>
<link name="link">
<collision name="collision">
@@ -65,15 +49,10 @@
<mu2>50</mu2>
</ode>
</friction>
<bounce/>
<contact>
<ode/>
</contact>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name="visual">
<cast_shadows>0</cast_shadows>
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
@@ -81,18 +60,10 @@
</plane>
</geometry>
<material>
<script>
<name>Kitchen/Grass</name>
</script>
<ambient>0.3 0.5 0.3 1</ambient>
<diffuse>0.3 0.5 0.3 1</diffuse>
</material>
</visual>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
</model>
<model name="wall1">
@@ -108,11 +79,6 @@
<size>15 0.2 5.0</size>
</box>
</geometry>
<surface>
<contact>
<collide_bitmask>0x02</collide_bitmask>
</contact>
</surface>
</collision>
<visual name="wall_brand_visual">
<geometry>
@@ -121,9 +87,8 @@
</box>
</geometry>
<material>
<script>
<name>Gazebo/Bricks</name>
</script>
<ambient>0.7 0.3 0.2 1</ambient>
<diffuse>0.7 0.3 0.2 1</diffuse>
</material>
</visual>
</link>
@@ -141,11 +106,6 @@
<size>15 0.2 5.0</size>
</box>
</geometry>
<surface>
<contact>
<collide_bitmask>0x02</collide_bitmask>
</contact>
</surface>
</collision>
<visual name="wall_visual">
<geometry>
@@ -154,9 +114,8 @@
</box>
</geometry>
<material>
<script>
<name>Gazebo/Bricks</name>
</script>
<ambient>0.7 0.3 0.2 1</ambient>
<diffuse>0.7 0.3 0.2 1</diffuse>
</material>
</visual>
</link>
@@ -174,11 +133,6 @@
<size>15 0.2 5.0</size>
</box>
</geometry>
<surface>
<contact>
<collide_bitmask>0x02</collide_bitmask>
</contact>
</surface>
</collision>
<visual name="wall_visual">
<geometry>
@@ -187,9 +141,8 @@
</box>
</geometry>
<material>
<script>
<name>Gazebo/Bricks</name>
</script>
<ambient>0.7 0.3 0.2 1</ambient>
<diffuse>0.7 0.3 0.2 1</diffuse>
</material>
</visual>
</link>
@@ -207,11 +160,6 @@
<size>15 0.2 5.0</size>
</box>
</geometry>
<surface>
<contact>
<collide_bitmask>0x02</collide_bitmask>
</contact>
</surface>
</collision>
<visual name="wall_visual">
<geometry>
@@ -220,13 +168,11 @@
</box>
</geometry>
<material>
<script>
<name>Gazebo/Bricks</name>
</script>
<ambient>0.7 0.3 0.2 1</ambient>
<diffuse>0.7 0.3 0.2 1</diffuse>
</material>
</visual>
</link>
</model>
</world>
</sdf>
+1 -1
View File
@@ -1,2 +1,2 @@
<program command="sw/tools/gzclient_launcher.sh" name="Gazebo" />
<program command="sw/tools/gzclient_launcher.sh" name="Gazebo Harmonic" />
File diff suppressed because it is too large Load Diff
+4 -4
View File
@@ -1,6 +1,6 @@
#!/bin/sh
# This script sets up the GAZEBO_MODEL_PATH for the gazebo client.
export GAZEBO_MODEL_PATH="$PAPARAZZI_HOME/conf/simulator/gazebo/models:$GAZEBO_MODEL_PATH"
export GAZEBO_MODEL_PATH="$PAPARAZZI_HOME/sw/ext/tudelft_gazebo_models/models:$GAZEBO_MODEL_PATH"
exec gzclient
# This script sets up the resource paths and launches the Gazebo Harmonic GUI client.
export GZ_SIM_RESOURCE_PATH="$PAPARAZZI_HOME/conf/simulator/gazebo/models:$GZ_SIM_RESOURCE_PATH"
export GZ_SIM_RESOURCE_PATH="$PAPARAZZI_HOME/sw/ext/tudelft_gazebo_models/models:$GZ_SIM_RESOURCE_PATH"
exec gz sim -g
+4 -6
View File
@@ -1,15 +1,13 @@
#!/bin/sh
# This script sets up environment variables for gazebo_ros
# This script sets up environment variables for Gazebo Harmonic with ROS
# Paparazzi paths
export GAZEBO_MODEL_PATH="$PAPARAZZI_HOME/conf/simulator/gazebo/models:$GAZEBO_MODEL_PATH"
export GAZEBO_MODEL_PATH="$PAPARAZZI_HOME/sw/ext/tudelft_gazebo_models/models:$GAZEBO_MODEL_PATH"
export GZ_SIM_RESOURCE_PATH="$PAPARAZZI_HOME/conf/simulator/gazebo/models:$GZ_SIM_RESOURCE_PATH"
export GZ_SIM_RESOURCE_PATH="$PAPARAZZI_HOME/sw/ext/tudelft_gazebo_models/models:$GZ_SIM_RESOURCE_PATH"
# ROS and Gazebo defaults
# ROS defaults
ROS_SETUP=`locate --regex 'ros/[a-z]*/setup.sh$'`
GAZEBO_SETUP=`locate --regex 'gazebo/setup.sh$'`
. $ROS_SETUP
. $GAZEBO_SETUP
# Launch NPS-Gazebo
exec $PAPARAZZI_HOME/sw/simulator/pprzsim-launch $@