Skip to content

Commit

Permalink
Adding tiltrotor to gazebo simulation (#66)
Browse files Browse the repository at this point in the history
* First draft

* Update to gz harmonic, including colors, plugins, sensors

* Move the motor block on top of the bar, use clockwise orientations for mesh, and adjust angular ranges to +-90 deg

* Tuning

* Set coherent limits with PX4 servo settings

* reuse meshes that exist

* Set servo number coherent with airframe file
  • Loading branch information
Perrrewi authored Dec 18, 2024
1 parent 19fd924 commit 230450c
Show file tree
Hide file tree
Showing 6 changed files with 989 additions and 42 deletions.
30 changes: 12 additions & 18 deletions models/advanced_plane/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -360,9 +360,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -389,9 +388,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -418,9 +416,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -447,9 +444,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -476,9 +472,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -505,9 +500,8 @@
<axis>
<xyz>0 0 1</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand Down
6 changes: 2 additions & 4 deletions models/lawnmower/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -572,7 +572,6 @@
</joint>
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>right_wheel_joint</joint_name>
<!--sub_topic>servo_0</sub_topic-->
<sub_topic>command/motor_speed</sub_topic>
<use_actuator_msg>true</use_actuator_msg>
<actuator_number>0</actuator_number>
Expand All @@ -589,7 +588,6 @@
</plugin>
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>left_wheel_joint</joint_name>
<!--sub_topic>servo_1</sub_topic-->
<sub_topic>command/motor_speed</sub_topic>
<use_actuator_msg>true</use_actuator_msg>
<actuator_number>1</actuator_number>
Expand All @@ -607,15 +605,15 @@
<!-- Note: SIM_GZ_SV_FAIL1 defines servo_0 etc. -->
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>cutter_blades_joint</joint_name>
<sub_topic>servo_2</sub_topic>
<sub_topic>servo_0</sub_topic>
<!-- p_gain>1.0</p_gain>
<cmd_max>2000.0</cmd_max>
<cmd_min>1000.0</cmd_min>
<cmd_offset>0.0</cmd_offset -->
</plugin>
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>engine_visual_joint</joint_name>
<sub_topic>servo_3</sub_topic>
<sub_topic>servo_1</sub_topic>
<p_gain>10.0</p_gain>
<!-- use_actuator_msg>false</use_actuator_msg>
<initial_velocity>0</initial_velocity>
Expand Down
25 changes: 12 additions & 13 deletions models/rc_cessna/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -567,8 +567,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -587,8 +587,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -607,8 +607,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -627,8 +627,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -647,9 +647,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -668,8 +667,8 @@
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand Down
13 changes: 6 additions & 7 deletions models/standard_vtol/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -598,8 +598,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -618,8 +618,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand All @@ -638,9 +638,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<!-- -30/+30 deg. -->
<lower>-0.53</lower>
<upper>0.53</upper>
<lower>-0.78</lower>
<upper>0.78</upper>
</limit>
<dynamics>
<damping>1.000</damping>
Expand Down
15 changes: 15 additions & 0 deletions models/tiltrotor/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<model>
<name>tiltrotor</name>
<version>1.0</version>
<sdf version='1.4'>model.sdf</sdf>

<author>
<name>Pernilla Wikström</name>
<email>[email protected]</email>
</author>

<description>
This is a model for a quad-tiltrotor with motors in x configuration.
</description>
</model>
Loading

0 comments on commit 230450c

Please sign in to comment.