Skip to content
This repository has been archived by the owner on Aug 5, 2024. It is now read-only.

Commit

Permalink
Added Sikorsky-X2 model and ardupilot demo world
Browse files Browse the repository at this point in the history
  • Loading branch information
SwiftGust committed May 19, 2017
1 parent 7722703 commit 5d09fb2
Show file tree
Hide file tree
Showing 30 changed files with 4,163 additions and 2,033 deletions.
715 changes: 715 additions & 0 deletions .tags

Large diffs are not rendered by default.

17 changes: 17 additions & 0 deletions gazebo_models/Sikorsky-X2_with_Ardupilot/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>

<model>
<name>Sikorsky-X2_with_ArduPilot</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>

<author>
<name>Seunghwan Jo</name>
<email>[email protected]</email>
</author>


<description>
Compound Coaxial Helicopter Sikorsky X2's RC model with ArduPilot
</description>
</model>
124 changes: 124 additions & 0 deletions gazebo_models/Sikorsky-X2_with_Ardupilot/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
<?xml version='1.0'?>
<sdf version='1.6'>
<model name="Sikorsky-X2_ArduPilot">
<pose>0 0 0 0 0 0</pose>
<include>
<uri>model://sikorsky-X2</uri>
<pose>0 0 0.2 0 0 0</pose>
</include>
<link name="cam_link">
<pose>0 0 0 0 0 0 </pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.001</ixx>
<iyy>0.001</iyy>
<izz>0.001</izz>
</inertia>
</inertial>
<sensor name="chase_cam" type="camera">
<pose>-3 -1 1.4 0 0.37 0</pose>
<camera>
<horizontal_fov>1.2</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
</image>
<clip>
<near>0.1</near>
<far>1000</far>
</clip>
</camera>
<always_on>0</always_on>
<update_rate>60</update_rate>
<visualize>false</visualize>
</sensor>
</link>
<joint name="camera_mount" type="fixed">
<child>cam_link</child>
<parent>sikorsky-X2::base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>

<plugin name="ardupilot_plugin" filename="libArduPilotPlugin.so">
<fdm_addr>127.0.0.1</fdm_addr>
<fdm_port_in>9002</fdm_port_in>
<fdm_port_out>9003</fdm_port_out>
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
<imuName>Sikorsky-X2_ArduPilot::sikorsky-X2::imu_link::imu_sensor</imuName>
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
<!--
incoming control command [0, 1]
so offset it by 0 to get [0, 1]
and divide max target by 1.
offset = 0
multiplier = 838 max rpm / 1 = 838
-->

<control channel="0">
<multiplier>1</multiplier>
<offset>-0.5</offset>
<type>POSITION</type>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>10</cmd_max>
<cmd_min>-10</cmd_min>
<jointName>sikorsky-X2::swashplate_joint</jointName>
</control>

<control channel="1">
<multiplier>1</multiplier>
<offset>-0.5</offset>
<type>POSITION</type>
<p_gain>10</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>10</cmd_max>
<cmd_min>-10</cmd_min>
<jointName>sikorsky-X2::swashplate2_joint</jointName>
</control>

<control channel="4">
<multiplier>838</multiplier>
<offset>0</offset>
<type>VELOCITY</type>
<p_gain>1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>10</cmd_max>
<cmd_min>0</cmd_min>
<jointName>sikorsky-X2::blade_up_joint</jointName>
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
</control>
<control channel="5">
<multiplier>-838</multiplier>
<offset>0</offset>
<type>VELOCITY</type>
<p_gain>1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
<i_max>0</i_max>
<i_min>0</i_min>
<cmd_max>0</cmd_max>
<cmd_min>-10</cmd_min>
<jointName>sikorsky-X2::blade_down_joint</jointName>
</control>
-->
</plugin>

</model>
</sdf>
12 changes: 10 additions & 2 deletions gazebo_models/cessna/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
</visual>

<!-- Debug - Centers of pressure -->
<!--<visual name="cp_left_wing">
<visual name="cp_left_wing">
<pose>-1 2.205 1.5 0 0 0</pose>
<geometry>
<sphere><radius>0.1</radius></sphere>
Expand All @@ -60,7 +60,7 @@
<geometry>
<sphere><radius>0.1</radius></sphere>
</geometry>
</visual>-->
</visual>-

</link>

Expand Down Expand Up @@ -281,6 +281,14 @@
</mesh>
</geometry>
</visual>
<visual name="prop_cp">
<pose>-0.37 0 0.77 0 0 0</pose>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</visual>
</link>

<link name="front_wheel">
Expand Down
Binary file added gazebo_models/gazebo_models.tar.gz
Binary file not shown.
Loading

1 comment on commit 5d09fb2

@SwiftGust
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Added some gazebo models and world
take
gazebo_models/sikorsky-X2
gazebo_models/Sikorsky-X2_with-ArduPilot
gazebo_models/ZED_stereocamera
if you interested.
and
gazebo_worlds/X2_ardupilot.world

Please sign in to comment.