diff --git a/ros_packages/mrs_uav_gazebo_simulation/models/mrs_robots_description/sdf/component_snippets.sdf.jinja b/ros_packages/mrs_uav_gazebo_simulation/models/mrs_robots_description/sdf/component_snippets.sdf.jinja
index d4a8d1a..a2212a9 100644
--- a/ros_packages/mrs_uav_gazebo_simulation/models/mrs_robots_description/sdf/component_snippets.sdf.jinja
+++ b/ros_packages/mrs_uav_gazebo_simulation/models/mrs_robots_description/sdf/component_snippets.sdf.jinja
@@ -844,29 +844,27 @@ limitations under the License.
{%- macro gps_macro(gps_name, parent_link, update_rate, gps_noise, gps_xy_random_walk, gps_z_random_walk, gps_xy_noise_density, gps_z_noise_density, gps_vxy_noise_density, gps_vz_noise_density, x, y, z, roll, pitch, yaw) -%}
-
-
- {{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}
- {{ zero_inertial_macro() }}
-
-
-
- {{ update_rate }}
- {{ gps_noise }}
- {{ gps_xy_random_walk }}
- {{ gps_z_random_walk }}
- {{ gps_xy_noise_density }}
- {{ gps_z_noise_density }}
- {{ gps_vxy_noise_density }}
- {{ gps_vz_noise_density }}
- {{ gps_name }}
-
-
-
-
+
+ {{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}
+ {{ zero_inertial_macro() }}
+
+
+
+ {{ update_rate }}
+ {{ gps_noise }}
+ {{ gps_xy_random_walk }}
+ {{ gps_z_random_walk }}
+ {{ gps_xy_noise_density }}
+ {{ gps_z_noise_density }}
+ {{ gps_vxy_noise_density }}
+ {{ gps_vz_noise_density }}
+ {{ gps_name }}
+
+
+
- {{ gps_name }}::link
+ {{ gps_name }}_link
{{ parent_link }}
@@ -1238,7 +1236,7 @@ limitations under the License.
{%- macro garmin_macro(sensor_name, parent_link, x, y, z, roll, pitch, yaw) -%}
-
+
{{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}
{{ zero_inertial_macro() }}
@@ -1290,7 +1288,7 @@ limitations under the License.
{{ parent_link }}
- {{ sensor_name }}::link
+ {{ sensor_name }}_link
{%- endmacro -%}