Skip to content

Commit 155f58e

Browse files
authored
Add OmniQuad platform (#133)
* Added Omniquad model config and SDF * [fix] refactor omniquad model - Created a base model to hold common drone geometry and sensors - Simplified main model to handle just plugin loading * update meshes and added missing license * removed separate LICENSE, link directly repo LICENSE now
1 parent ce203df commit 155f58e

8 files changed

Lines changed: 1158 additions & 0 deletions

File tree

models/omniquad/model.config

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
<?xml version="1.0"?>
2+
<model>
3+
<name>omniquad</name>
4+
<version>1.0</version>
5+
<sdf version="1.9">model.sdf</sdf>
6+
<license>https://github.com/PX4/PX4-gazebo-models/blob/main/LICENSE</license>
7+
<author>
8+
<name>Andrea Berra</name>
9+
<email>andrea.berra@outlook.com</email>
10+
</author>
11+
<description>Model of the Omniquad platform.</description>
12+
</model>

models/omniquad/model.sdf

Lines changed: 120 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<sdf version='1.9'>
3+
<model name='omniquad'>
4+
<include merge='true'>
5+
<uri>model://omniquad_base</uri>
6+
<pose>0 0 .2 0 0 0</pose>
7+
</include>
8+
9+
<!-- motor -->
10+
<plugin filename="gz-sim-multicopter-motor-model-system"
11+
name="gz::sim::systems::MulticopterMotorModel">
12+
<jointName>rotor_1_joint</jointName>
13+
<linkName>rotor_1</linkName>
14+
<turningDirection>ccw</turningDirection>
15+
<timeConstantUp>0.0125</timeConstantUp>
16+
<timeConstantDown>0.025</timeConstantDown>
17+
<maxRotVelocity>1100.0</maxRotVelocity>
18+
<motorConstant>9.84e-06</motorConstant>
19+
<momentConstant>0.09</momentConstant>
20+
<commandSubTopic>command/motor_speed</commandSubTopic>
21+
<motorNumber>0</motorNumber>
22+
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
23+
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
24+
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
25+
<motorType>velocity</motorType>
26+
</plugin>
27+
<plugin filename="gz-sim-multicopter-motor-model-system"
28+
name="gz::sim::systems::MulticopterMotorModel">
29+
<jointName>rotor_2_joint</jointName>
30+
<linkName>rotor_2</linkName>
31+
<turningDirection>ccw</turningDirection>
32+
<timeConstantUp>0.0125</timeConstantUp>
33+
<timeConstantDown>0.025</timeConstantDown>
34+
<maxRotVelocity>1000.0</maxRotVelocity>
35+
<motorConstant>9.84e-06</motorConstant>
36+
<momentConstant>0.09</momentConstant>
37+
<commandSubTopic>command/motor_speed</commandSubTopic>
38+
<motorNumber>1</motorNumber>
39+
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
40+
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
41+
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
42+
<motorType>velocity</motorType>
43+
</plugin>
44+
<plugin filename="gz-sim-multicopter-motor-model-system"
45+
name="gz::sim::systems::MulticopterMotorModel">
46+
<jointName>rotor_3_joint</jointName>
47+
<linkName>rotor_3</linkName>
48+
<turningDirection>cw</turningDirection>
49+
<timeConstantUp>0.0125</timeConstantUp>
50+
<timeConstantDown>0.025</timeConstantDown>
51+
<maxRotVelocity>1000.0</maxRotVelocity>
52+
<motorConstant>9.84e-06</motorConstant>
53+
<momentConstant>0.09</momentConstant>
54+
<commandSubTopic>command/motor_speed</commandSubTopic>
55+
<motorNumber>2</motorNumber>
56+
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
57+
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
58+
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
59+
<motorType>velocity</motorType>
60+
</plugin>
61+
<plugin filename="gz-sim-multicopter-motor-model-system"
62+
name="gz::sim::systems::MulticopterMotorModel">
63+
<jointName>rotor_4_joint</jointName>
64+
<linkName>rotor_4</linkName>
65+
<turningDirection>cw</turningDirection>
66+
<timeConstantUp>0.0125</timeConstantUp>
67+
<timeConstantDown>0.025</timeConstantDown>
68+
<maxRotVelocity>1000.0</maxRotVelocity>
69+
<motorConstant>9.84e-06</motorConstant>
70+
<momentConstant>0.09</momentConstant>
71+
<commandSubTopic>command/motor_speed</commandSubTopic>
72+
<motorNumber>3</motorNumber>
73+
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
74+
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
75+
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
76+
<motorType>velocity</motorType>
77+
</plugin>
78+
<!-- servo -->
79+
<plugin filename="gz-sim-joint-position-controller-system"
80+
name="gz::sim::systems::JointPositionController">
81+
<joint_name>tilt_arm_1_joint</joint_name>
82+
<sub_topic>servo_0</sub_topic>
83+
<p_gain>10.0</p_gain>
84+
<i_gain>0.0</i_gain>
85+
<d_gain>0.25</d_gain>
86+
<cmd_max>2</cmd_max>
87+
<cmd_min>-2</cmd_min>
88+
</plugin>
89+
<plugin filename="gz-sim-joint-position-controller-system"
90+
name="gz::sim::systems::JointPositionController">
91+
<joint_name>tilt_arm_2_joint</joint_name>
92+
<sub_topic>servo_1</sub_topic>
93+
<p_gain>10.0</p_gain>
94+
<i_gain>0.0</i_gain>
95+
<d_gain>0.25</d_gain>
96+
<cmd_max>2</cmd_max>
97+
<cmd_min>-2</cmd_min>
98+
</plugin>
99+
<plugin filename="gz-sim-joint-position-controller-system"
100+
name="gz::sim::systems::JointPositionController">
101+
<joint_name>tilt_arm_3_joint</joint_name>
102+
<sub_topic>servo_2</sub_topic>
103+
<p_gain>10.0</p_gain>
104+
<i_gain>0.0</i_gain>
105+
<d_gain>0.25</d_gain>
106+
<cmd_max>2</cmd_max>
107+
<cmd_min>-2</cmd_min>
108+
</plugin>
109+
<plugin filename="gz-sim-joint-position-controller-system"
110+
name="gz::sim::systems::JointPositionController">
111+
<joint_name>tilt_arm_4_joint</joint_name>
112+
<sub_topic>servo_3</sub_topic>
113+
<p_gain>10.0</p_gain>
114+
<i_gain>0.0</i_gain>
115+
<d_gain>0.25</d_gain>
116+
<cmd_max>2</cmd_max>
117+
<cmd_min>-2</cmd_min>
118+
</plugin>
119+
</model>
120+
</sdf>
12.6 KB
Binary file not shown.
215 KB
Binary file not shown.

models/omniquad_base/meshes/iris_prop_ccw.dae

Lines changed: 160 additions & 0 deletions
Large diffs are not rendered by default.

models/omniquad_base/meshes/iris_prop_cw.dae

Lines changed: 160 additions & 0 deletions
Large diffs are not rendered by default.

models/omniquad_base/model.config

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
<?xml version="1.0"?>
2+
<model>
3+
<name>omniquad_base</name>
4+
<version>1.0</version>
5+
<sdf version="1.9">model.sdf</sdf>
6+
<license>https://github.com/PX4/PX4-gazebo-models/blob/main/LICENSE</license>
7+
<author>
8+
<name>Andrea Berra</name>
9+
<email>andrea.berra@outlook.com</email>
10+
</author>
11+
<description>Model of the Omniquad platform.</description>
12+
</model>

0 commit comments

Comments
 (0)