Skip to content

Commit

Permalink
fix: problems with thrusters
Browse files Browse the repository at this point in the history
  • Loading branch information
Pedro-Roque committed May 15, 2024
1 parent 11693db commit 8c784ea
Showing 1 changed file with 30 additions and 31 deletions.
61 changes: 30 additions & 31 deletions models/3d_spacecraft/3d_spacecraft.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,19 @@
<model name='dart'>
<link name='body'>
<inertial>
<pose>0 0 0.2 0 -0 0</pose>
<mass>12.5</mass>
<pose>0 0 0 0 -0 0</pose>
<mass>648</mass>
<inertia>
<ixx>0.1454</ixx>
<ixx>1024</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1366</iyy>
<iyy>1024</iyy>
<iyz>0</iyz>
<izz>0.1594</izz>
<izz>1024</izz>
</inertia>
</inertial>
<collision name='body_collision'>
<pose>0 0 0.25 0 -0 0</pose>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.5</length>
Expand Down Expand Up @@ -49,7 +49,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_0_joint' type='fixed'>
<pose relative_to='body'>-0.12 0.12 0.2 3.14159 1.57079 3.14159</pose>
<pose relative_to='body'>-0.50 -0.50 0 -1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_0</child>
<axis>
Expand Down Expand Up @@ -89,7 +89,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_1_joint' type='fixed'>
<pose relative_to='body'>0.12 0.12 0.2 3.14159 -1.57079 3.14159</pose>
<pose relative_to='body'>0.50 -0.50 0 -1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_1</child>
<axis>
Expand Down Expand Up @@ -129,7 +129,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_2_joint' type='fixed'>
<pose relative_to='body'>-0.12 -0.12 0.2 3.14159 1.57079 3.14159</pose>
<pose relative_to='body'>0.50 0.50 0 1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_2</child>
<axis>
Expand Down Expand Up @@ -169,7 +169,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_3_joint' type='fixed'>
<pose relative_to='body'>0.12 -0.12 0.2 3.14159 -1.57079 3.14159</pose>
<pose relative_to='body'>-0.50 0.50 0 1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_3</child>
<axis>
Expand Down Expand Up @@ -209,7 +209,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_4_joint' type='fixed'>
<pose relative_to='body'>0.12 0.12 0.2 1.5708 -0 0</pose>
<pose relative_to='body'>-0.50 0.0 0.50 0 1.5708 0</pose>
<parent>body</parent>
<child>thruster_4</child>
<axis>
Expand Down Expand Up @@ -249,7 +249,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_5_joint' type='fixed'>
<pose relative_to='body'>0.12 -0.12 0.2 -1.5708 0 0</pose>
<pose relative_to='body'>0.50 0.0 0.50 0 -1.5708 0</pose>
<parent>body</parent>
<child>thruster_5</child>
<axis>
Expand Down Expand Up @@ -289,7 +289,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_6_joint' type='fixed'>
<pose relative_to='body'>-0.12 0.12 0.2 1.5708 -0 0</pose>
<pose relative_to='body'>0.50 0.0 -0.50 0 -1.5708 0</pose>
<parent>body</parent>
<child>thruster_6</child>
<axis>
Expand Down Expand Up @@ -329,7 +329,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_7_joint' type='fixed'>
<pose relative_to='body'>-0.12 -0.12 0.2 -1.5708 0 0</pose>
<pose relative_to='body'>-0.50 0.0 -0.50 0 1.5708 0</pose>
<parent>body</parent>
<child>thruster_7</child>
<axis>
Expand Down Expand Up @@ -368,9 +368,8 @@
</inertial>
<gravity>0</gravity>
</link>

<joint name='thruster_8_joint' type='fixed'>
<pose relative_to='body'>0.12 0 0.4 3.1415 0 0</pose>
<pose relative_to='body'>0.0 0.50 0.50 1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_8</child>
<axis>
Expand Down Expand Up @@ -410,7 +409,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_9_joint' type='fixed'>
<pose relative_to='body'>0.12 0 0.0 0 0 0</pose>
<pose relative_to='body'>0.0 -0.50 0.50 -1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_9</child>
<axis>
Expand Down Expand Up @@ -450,7 +449,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_10_joint' type='fixed'>
<pose relative_to='body'>-0.12 0 0.4 3.1415 0 0</pose>
<pose relative_to='body'>0.0 -0.50 -0.50 -1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_10</child>
<axis>
Expand Down Expand Up @@ -490,7 +489,7 @@
<gravity>0</gravity>
</link>
<joint name='thruster_11_joint' type='fixed'>
<pose relative_to='body'>-0.12 0 0.0 0 0 0</pose>
<pose relative_to='body'>0.0 0.50 -0.50 1.5708 0 0</pose>
<parent>body</parent>
<child>thruster_11</child>
<axis>
Expand Down Expand Up @@ -535,95 +534,95 @@
<thrusterNumber>0</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_1_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_1</linkName>
<thrusterNumber>1</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_2_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_2</linkName>
<thrusterNumber>2</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_3_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_3</linkName>
<thrusterNumber>3</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_4_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_4</linkName>
<thrusterNumber>4</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_5_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_5</linkName>
<thrusterNumber>5</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_6_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_6</linkName>
<thrusterNumber>6</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_7_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_7</linkName>
<thrusterNumber>7</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_8_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_8</linkName>
<thrusterNumber>8</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_9_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_9</linkName>
<thrusterNumber>9</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_10_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_10</linkName>
<thrusterNumber>10</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<plugin name='thruster_11_model' filename='libgazebo_coldgas_thruster_plugin.so'>
<robotNamespace/>
<linkName>thruster_11</linkName>
<thrusterNumber>11</thrusterNumber>
<commandSubTopic>/gazebo/command/actuator_outputs</commandSubTopic>
<pwmFrequency>10</pwmFrequency>
<maxThrust>1.4</maxThrust>
<maxThrust>0.237</maxThrust>
</plugin>
<static>0</static>
<plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
Expand Down

0 comments on commit 8c784ea

Please sign in to comment.