Skip to content

Commit

Permalink
Models: update world orientation and fixes for Harmonic
Browse files Browse the repository at this point in the history
- Anemometer: use degrees.
- Gimbal 1D: use degrees in pose.
- Gimbal 2D: use degrees in pose.
- Parachute: update plugin filename.
- Iris: use degrees, replace -0 with 0.
- Iris: remove z-offset from iris_with_standoffs model.
  - Remove z-offset from iris_with_standoffs, so model origin is at CoM.
  - Set pose in world file.
- Zephyr: use degrees.
- Zephyr: update parachute plugin name.
- Zephyr: disable moment coefficient contribution.
  - Required due to changed behaviour in Gazebo Harmonic.
- Update gimbal pose in iris_with_gimbal world.
- Update iris_warehouse world.
- Forward port remaining changes from `main`.

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Jan 14, 2024
1 parent 1caa507 commit e4bbcf3
Show file tree
Hide file tree
Showing 17 changed files with 295 additions and 128 deletions.
2 changes: 1 addition & 1 deletion models/gimbal_small_1d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@
</geometry>
</collision>
<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<pose degrees="true">0 0 0 -90 -90 0</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
Expand Down
2 changes: 1 addition & 1 deletion models/gimbal_small_2d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@
</geometry>
</collision>
<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<pose degrees="true">0 0 0 -90 -90 0</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
Expand Down
88 changes: 44 additions & 44 deletions models/iris_with_ardupilot/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -79,9 +79,9 @@
</link>
<link name="rotor_0_blade_2_cp">
<gravity>0</gravity>
<pose>0.13 -0.22 0.216 0 -0 0</pose>
<pose>0.13 -0.22 0.216 0 0 0</pose>
<visual name='rotor_0_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -93,7 +93,7 @@
</material>
</visual>
<visual name='rotor_0_visual_tip'>
<pose>-0.12 0 0 0 -0 0</pose>
<pose>-0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -105,7 +105,7 @@
</material>
</visual>
<visual name='rotor_0_visual_cp'>
<pose>-0.084 0 0 0 -0 0</pose>
<pose>-0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -117,7 +117,7 @@
</material>
</visual>
<visual name='rotor_0_visual_cp_forward'>
<pose>-0.084 -0.02 0 0 -0 0</pose>
<pose>-0.084 -0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -129,7 +129,7 @@
</material>
</visual>
<visual name='rotor_0_visual_cp_upward'>
<pose>-0.084 0 0.02 0 -0 0</pose>
<pose>-0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand Down Expand Up @@ -166,9 +166,9 @@
<link name="rotor_1_blade_1_cp">
<gravity>0</gravity>
<pose>-0.13 0.2 0.216 0 -0 0</pose>
<pose>-0.13 0.2 0.216 0 0 0</pose>
<visual name='rotor_1_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -180,7 +180,7 @@
</material>
</visual>
<visual name='rotor_1_visual_tip'>
<pose>0.12 0 0 0 -0 0</pose>
<pose>0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -192,7 +192,7 @@
</material>
</visual>
<visual name='rotor_1_visual_cp'>
<pose>0.084 0 0 0 -0 0</pose>
<pose>0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -204,7 +204,7 @@
</material>
</visual>
<visual name='rotor_1_visual_cp_forward'>
<pose>0.084 0.02 0 0 -0 0</pose>
<pose>0.084 0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -216,7 +216,7 @@
</material>
</visual>
<visual name='rotor_1_visual_cp_upward'>
<pose>0.084 0 0.02 0 -0 0</pose>
<pose>0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -230,9 +230,9 @@
</link>
<link name="rotor_1_blade_2_cp">
<gravity>0</gravity>
<pose>-0.13 0.2 0.216 0 -0 0</pose>
<pose>-0.13 0.2 0.216 0 0 0</pose>
<visual name='rotor_1_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -244,7 +244,7 @@
</material>
</visual>
<visual name='rotor_1_visual_tip'>
<pose>-0.12 0 0 0 -0 0</pose>
<pose>-0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -256,7 +256,7 @@
</material>
</visual>
<visual name='rotor_1_visual_cp'>
<pose>-0.084 0 0 0 -0 0</pose>
<pose>-0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -268,7 +268,7 @@
</material>
</visual>
<visual name='rotor_1_visual_cp_forward'>
<pose>-0.084 -0.02 0 0 -0 0</pose>
<pose>-0.084 -0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -280,7 +280,7 @@
</material>
</visual>
<visual name='rotor_1_visual_cp_upward'>
<pose>-0.084 0 0.02 0 -0 0</pose>
<pose>-0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand Down Expand Up @@ -317,9 +317,9 @@
<link name="rotor_2_blade_1_cp">
<gravity>0</gravity>
<pose>0.13 0.22 0.216 0 -0 0</pose>
<pose>0.13 0.22 0.216 0 0 0</pose>
<visual name='rotor_2_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -331,7 +331,7 @@
</material>
</visual>
<visual name='rotor_2_visual_tip'>
<pose>0.12 0 0 0 -0 0</pose>
<pose>0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -343,7 +343,7 @@
</material>
</visual>
<visual name='rotor_2_visual_cp'>
<pose>0.084 0 0 0 -0 0</pose>
<pose>0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -355,7 +355,7 @@
</material>
</visual>
<visual name='rotor_2_visual_cp_forward'>
<pose>0.084 -0.02 0 0 -0 0</pose>
<pose>0.084 -0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -367,7 +367,7 @@
</material>
</visual>
<visual name='rotor_2_visual_cp_upward'>
<pose>0.084 0 0.02 0 -0 0</pose>
<pose>0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -381,9 +381,9 @@
</link>
<link name="rotor_2_blade_2_cp">
<gravity>0</gravity>
<pose>0.13 0.22 0.216 0 -0 0</pose>
<pose>0.13 0.22 0.216 0 0 0</pose>
<visual name='rotor_2_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -395,7 +395,7 @@
</material>
</visual>
<visual name='rotor_2_visual_tip'>
<pose>-0.12 0 0 0 -0 0</pose>
<pose>-0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -407,7 +407,7 @@
</material>
</visual>
<visual name='rotor_2_visual_cp'>
<pose>-0.084 0 0 0 -0 0</pose>
<pose>-0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -419,7 +419,7 @@
</material>
</visual>
<visual name='rotor_2_visual_cp_forward'>
<pose>-0.084 0.02 0 0 -0 0</pose>
<pose>-0.084 0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -431,7 +431,7 @@
</material>
</visual>
<visual name='rotor_2_visual_cp_upward'>
<pose>-0.084 0 0.02 0 -0 0</pose>
<pose>-0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand Down Expand Up @@ -468,9 +468,9 @@
<link name="rotor_3_blade_1_cp">
<gravity>0</gravity>
<pose>-0.13 -0.2 0.216 0 -0 0</pose>
<pose>-0.13 -0.2 0.216 0 0 0</pose>
<visual name='rotor_3_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -482,7 +482,7 @@
</material>
</visual>
<visual name='rotor_3_visual_tip'>
<pose>0.12 0 0 0 -0 0</pose>
<pose>0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -494,7 +494,7 @@
</material>
</visual>
<visual name='rotor_3_visual_cp'>
<pose>0.084 0 0 0 -0 0</pose>
<pose>0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -506,7 +506,7 @@
</material>
</visual>
<visual name='rotor_3_visual_cp_forward'>
<pose>0.084 -0.02 0 0 -0 0</pose>
<pose>0.084 -0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -518,7 +518,7 @@
</material>
</visual>
<visual name='rotor_3_visual_cp_upward'>
<pose>0.084 0 0.02 0 -0 0</pose>
<pose>0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -532,9 +532,9 @@
</link>
<link name="rotor_3_blade_2_cp">
<gravity>0</gravity>
<pose>-0.13 -0.2 0.216 0 -0 0</pose>
<pose>-0.13 -0.2 0.216 0 0 0</pose>
<visual name='rotor_3_visual_root'>
<pose>0 0 0 0 -0 0</pose>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -546,7 +546,7 @@
</material>
</visual>
<visual name='rotor_3_visual_tip'>
<pose>-0.12 0 0 0 -0 0</pose>
<pose>-0.12 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
Expand All @@ -558,7 +558,7 @@
</material>
</visual>
<visual name='rotor_3_visual_cp'>
<pose>-0.084 0 0 0 -0 0</pose>
<pose>-0.084 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -570,7 +570,7 @@
</material>
</visual>
<visual name='rotor_3_visual_cp_forward'>
<pose>-0.084 0.02 0 0 -0 0</pose>
<pose>-0.084 0.02 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand All @@ -582,7 +582,7 @@
</material>
</visual>
<visual name='rotor_3_visual_cp_upward'>
<pose>-0.084 0 0.02 0 -0 0</pose>
<pose>-0.084 0 0.02 0 0 0</pose>
<geometry>
<sphere>
<radius>0.003</radius>
Expand Down Expand Up @@ -791,8 +791,8 @@
<!-- Frame conventions
Require by ArduPilot: change model and gazebo from XYZ to XY-Z coordinates
-->
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
<modelXYZToAirplaneXForwardZDown degrees="true">0 0 0 180 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED degrees="true">0 0 0 180 0 90</gazeboXYZToNED>

<!-- Sensors -->
<imuName>iris_with_standoffs::imu_link::imu_sensor</imuName>
Expand Down
10 changes: 7 additions & 3 deletions models/iris_with_gimbal/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<include merge="true">
<uri>package://ardupilot_gazebo/models/gimbal_small_2d</uri>
<name>gimbal</name>
<pose>0 -0.01 -0.11 1.57 0 1.57</pose>
<pose degrees="true">0 -0.01 -0.124923 90 0 90</pose>
</include>

<joint name="gimbal_joint" type="revolute">
Expand Down Expand Up @@ -228,8 +228,12 @@
<fdm_port_in>9002</fdm_port_in>
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<lock_step>1</lock_step>
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 1.57079632</gazeboXYZToNED>

<!-- Frame conventions
Require by ArduPilot: change model and gazebo from XYZ to XY-Z coordinates
-->
<modelXYZToAirplaneXForwardZDown degrees="true">0 0 0 180 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED degrees="true">0 0 0 180 0 90</gazeboXYZToNED>

<!-- Sensors -->
<imuName>imu_link::imu_sensor</imuName>
Expand Down
Loading

0 comments on commit e4bbcf3

Please sign in to comment.