Skip to content

Commit

Permalink
Gimbal: add gimbal model modified for Gazebo Sim (#38)
Browse files Browse the repository at this point in the history
- Retrieve original model from http://models.gazebosim.org/gimbal_small_2d/
- Rename to reflect actual number of DOF: original has 1, upgraded has 2.
- Modify material elements for Gazebo Sim.
- Add gimbal to iris_with_ardupilot (plugin disabled).
- Add the sensors system configured for ogre2.
- Gimbal1d - copy from Gimbal2d and rename.
- Add stubs for joint position controller plugin.
- Gimbal2d - add arm joint.
- Gimbal2d - add joint position controller plugins for both arm and tilt joints.
- Add a test world for the gimbals in subfolder

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring authored Dec 21, 2022
1 parent 1808aba commit 446396c
Show file tree
Hide file tree
Showing 14 changed files with 1,320 additions and 7 deletions.
63 changes: 63 additions & 0 deletions models/gimbal_small_1d/meshes/base_arm.dae

Large diffs are not rendered by default.

63 changes: 63 additions & 0 deletions models/gimbal_small_1d/meshes/base_main.dae

Large diffs are not rendered by default.

63 changes: 63 additions & 0 deletions models/gimbal_small_1d/meshes/tilt.dae

Large diffs are not rendered by default.

20 changes: 20 additions & 0 deletions models/gimbal_small_1d/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0" ?>
<model>
<name>Gimbal Small 1D</name>
<version>2.0</version>
<sdf version="1.6">model.sdf</sdf>
<author>
<name>anonymous</name>
<email>anonymous</email>
</author>
<description>
1D gimbal for small camera (go pro size) on drone.
3D mesh: http://www.thingiverse.com/thing:397579
by: http://www.thingiverse.com/Motorpixiegimbals/about.

20 December, 2022: model retrieved from
http://models.gazebosim.org/gimbal_small_2d/
and modified for Gazebo Sim (material scripts replaced).
Renamed as this version has 1 DOF.
</description>
</model>
156 changes: 156 additions & 0 deletions models/gimbal_small_1d/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,156 @@
<?xml version='1.0'?>
<sdf version='1.6'>
<model name='gimbal_small_1d'>
<pose>0 0 0.18 0 0 0</pose>

<link name='base_link'>
<inertial>
<mass>0.2</mass>
<inertia>
<ixx>0.0001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0001</iyy>
<iyz>0</iyz>
<izz>0.0001</izz>
</inertia>
</inertial>

<visual name='base_main_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_1d/meshes/base_main.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.1 0.1 0.1</ambient>
<diffuse>0.1 0.1 0.1</diffuse>
<specular>0.01 0.01 0.01 1.0</specular>
</material>
</visual>

<visual name='base_arm_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_1d/meshes/base_arm.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.1 0.1 0.1</ambient>
<diffuse>0.1 0.1 0.1</diffuse>
<specular>0.01 0.01 0.01 1.0</specular>
</material>
</visual>

<collision name='base_col'>
<pose>0.01 0.075 -0.025 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.05 0.15</size>
</box>
</geometry>
</collision>
</link>

<link name='tilt_link'>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.00001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00001</iyy>
<iyz>0</iyz>
<izz>0.00001</izz>
</inertia>
</inertial>
<visual name='tilt_viz'>
<pose>0 0 -0.005 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_1d/meshes/tilt.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.4 0.4 0.4</ambient>
<diffuse>0.4 0.4 0.4</diffuse>
<specular>0.1 0.1 0.1 1.0</specular>
</material>
</visual>

<collision name='tilt_col'>
<pose>0 0 -0.005 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_1d/meshes/tilt.dae</uri>
</mesh>
</geometry>
</collision>

<visual name='camera_viz'>
<pose>0 0 0.02 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.050</length>
</cylinder>
</geometry>

<material>
<ambient>0.4 0.4 0.4</ambient>
<diffuse>0.4 0.4 0.4</diffuse>
<specular>0.1 0.1 0.1 1.0</specular>
</material>
</visual>

<collision name='camera_col'>
<pose>0 0 0.02 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.050</length>
</cylinder>
</geometry>
</collision>

<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>15000</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>1</visualize>
</sensor>
</link>

<joint name='tilt_joint' type='revolute'>
<parent>base_link</parent>
<child>tilt_link</child>
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.5</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>3.14159265</upper>
</limit>
</axis>
<pose>0 0 0.02 0 0 0</pose>
</joint>

</model>
</sdf>
63 changes: 63 additions & 0 deletions models/gimbal_small_2d/meshes/base_arm.dae

Large diffs are not rendered by default.

63 changes: 63 additions & 0 deletions models/gimbal_small_2d/meshes/base_main.dae

Large diffs are not rendered by default.

63 changes: 63 additions & 0 deletions models/gimbal_small_2d/meshes/tilt.dae

Large diffs are not rendered by default.

20 changes: 20 additions & 0 deletions models/gimbal_small_2d/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0" ?>
<model>
<name>Gimbal Small 2D</name>
<version>2.0</version>
<sdf version="1.6">model.sdf</sdf>
<author>
<name>anonymous</name>
<email>anonymous</email>
</author>
<description>
3D gimbal for small camera (go pro size) on drone.
3D mesh: http://www.thingiverse.com/thing:397579
by: http://www.thingiverse.com/Motorpixiegimbals/about.

20 December, 2022: model retrieved from
http://models.gazebosim.org/gimbal_small_2d/
and modified for Gazebo Sim (material scripts replaced)
Enable arm joint to provide 2 DOF.
</description>
</model>
195 changes: 195 additions & 0 deletions models/gimbal_small_2d/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,195 @@
<?xml version='1.0'?>
<sdf version='1.6'>
<model name='gimbal_small_2d'>
<pose>0 0 0.18 0 0 0</pose>

<link name='base_link'>
<inertial>
<mass>0.2</mass>
<inertia>
<ixx>0.0001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0001</iyy>
<iyz>0</iyz>
<izz>0.0001</izz>
</inertia>
</inertial>

<visual name='base_main_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_main.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.1 0.1 0.1</ambient>
<diffuse>0.1 0.1 0.1</diffuse>
<specular>0.01 0.01 0.01 1.0</specular>
</material>
</visual>

<collision name='base_col'>
<pose>0.01 0.075 -0.025 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.05 0.15</size>
</box>
</geometry>
</collision>
</link>

<link name='arm_link'>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.00001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00001</iyy>
<iyz>0</iyz>
<izz>0.00001</izz>
</inertia>
</inertial>

<visual name='arm_viz'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_arm.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.1 0.1 0.1</ambient>
<diffuse>0.1 0.1 0.1</diffuse>
<specular>0.01 0.01 0.01 1.0</specular>
</material>
</visual>

<collision name='arm_col'>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/base_arm.dae</uri>
</mesh>
</geometry>
</collision>
</link>

<joint name='arm_joint' type='revolute'>
<parent>base_link</parent>
<child>arm_link</child>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<damping>0.5</damping>
</dynamics>
<limit>
<lower>-3.14159265</lower>
<upper>3.14159265</upper>
</limit>
</axis>
<pose>0.01 0 -0.04 0 0 0</pose>
</joint>

<link name='tilt_link'>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.00001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00001</iyy>
<iyz>0</iyz>
<izz>0.00001</izz>
</inertia>
</inertial>
<visual name='tilt_viz'>
<pose>0 0 -0.005 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/tilt.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0.4 0.4 0.4</ambient>
<diffuse>0.4 0.4 0.4</diffuse>
<specular>0.1 0.1 0.1 1.0</specular>
</material>
</visual>

<collision name='tilt_col'>
<pose>0 0 -0.005 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://gimbal_small_2d/meshes/tilt.dae</uri>
</mesh>
</geometry>
</collision>

<visual name='camera_viz'>
<pose>0 0 0.02 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.050</length>
</cylinder>
</geometry>

<material>
<ambient>0.4 0.4 0.4</ambient>
<diffuse>0.4 0.4 0.4</diffuse>
<specular>0.1 0.1 0.1 1.0</specular>
</material>
</visual>

<collision name='camera_col'>
<pose>0 0 0.02 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.050</length>
</cylinder>
</geometry>
</collision>

<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<camera>
<horizontal_fov>2.0</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>15000</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>1</visualize>
</sensor>
</link>

<joint name='tilt_joint' type='revolute'>
<parent>arm_link</parent>
<child>tilt_link</child>
<axis>
<xyz>1 0 0</xyz>
<dynamics>
<damping>0.5</damping>
</dynamics>
<limit>
<lower>-1.57079632</lower>
<upper>3.14159265</upper>
</limit>
</axis>
<pose>0 0 0.02 0 0 0</pose>
</joint>

</model>
</sdf>
Loading

0 comments on commit 446396c

Please sign in to comment.