You cannot select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
219 lines
6.6 KiB
XML
219 lines
6.6 KiB
XML
<?xml version='1.0'?>
|
|
<sdf version="1.6" >
|
|
<model name="iris_demo">
|
|
<include>
|
|
<uri>model://iris_base</uri>
|
|
</include>
|
|
|
|
<!-- plugins -->
|
|
<plugin name="rotor_0_blade_1" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>0.084 0 0</cp>
|
|
<forward>0 1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_0</link_name>
|
|
</plugin>
|
|
<plugin name="rotor_0_blade_2" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>-0.084 0 0</cp>
|
|
<forward>0 -1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_0</link_name>
|
|
</plugin>
|
|
|
|
<plugin name="rotor_1_blade_1" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>0.084 0 0</cp>
|
|
<forward>0 1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_1</link_name>
|
|
</plugin>
|
|
<plugin name="rotor_1_blade_2" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>-0.084 0 0</cp>
|
|
<forward>0 -1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_1</link_name>
|
|
</plugin>
|
|
|
|
<plugin name="rotor_2_blade_1" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>0.084 0 0</cp>
|
|
<forward>0 -1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_2</link_name>
|
|
</plugin>
|
|
<plugin name="rotor_2_blade_2" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>-0.084 0 0</cp>
|
|
<forward>0 1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_2</link_name>
|
|
</plugin>
|
|
|
|
<plugin name="rotor_3_blade_1" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>0.084 0 0</cp>
|
|
<forward>0 -1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_3</link_name>
|
|
</plugin>
|
|
<plugin name="rotor_3_blade_2" filename="libLiftDragPlugin.so">
|
|
<a0>0.3</a0>
|
|
<alpha_stall>1.4</alpha_stall>
|
|
<cla>4.2500</cla>
|
|
<cda>0.10</cda>
|
|
<cma>0.00</cma>
|
|
<cla_stall>-0.025</cla_stall>
|
|
<cda_stall>0.0</cda_stall>
|
|
<cma_stall>0.0</cma_stall>
|
|
<area>0.002</area>
|
|
<air_density>1.2041</air_density>
|
|
<cp>-0.084 0 0</cp>
|
|
<forward>0 1 0</forward>
|
|
<upward>0 0 1</upward>
|
|
<link_name>iris::rotor_3</link_name>
|
|
</plugin>
|
|
<plugin name="arducopter_plugin" filename="libArduPilotPlugin.so">
|
|
<fdm_addr>127.0.0.1</fdm_addr>
|
|
<fdm_port_in>9032</fdm_port_in>
|
|
<fdm_port_out>9033</fdm_port_out>
|
|
<!--
|
|
Require by APM :
|
|
Only change model and gazebo from XYZ to XY-Z coordinates
|
|
-->
|
|
<modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
|
|
<gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
|
|
<imuName>iris::iris/imu_link::imu_sensor</imuName>
|
|
<connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
|
|
<control channel="0">
|
|
<!--
|
|
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
|
|
-->
|
|
<type>VELOCITY</type>
|
|
<offset>0</offset>
|
|
<p_gain>0.20</p_gain>
|
|
<i_gain>0</i_gain>
|
|
<d_gain>0</d_gain>
|
|
<i_max>0</i_max>
|
|
<i_min>0</i_min>
|
|
<cmd_max>2.5</cmd_max>
|
|
<cmd_min>-2.5</cmd_min>
|
|
<jointName>iris::rotor_0_joint</jointName>
|
|
<multiplier>838</multiplier>
|
|
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
|
|
</control>
|
|
<control channel="1">
|
|
<type>VELOCITY</type>
|
|
<offset>0</offset>
|
|
<p_gain>0.20</p_gain>
|
|
<i_gain>0</i_gain>
|
|
<d_gain>0</d_gain>
|
|
<i_max>0</i_max>
|
|
<i_min>0</i_min>
|
|
<cmd_max>2.5</cmd_max>
|
|
<cmd_min>-2.5</cmd_min>
|
|
<jointName>iris::rotor_1_joint</jointName>
|
|
<multiplier>838</multiplier>
|
|
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
|
|
</control>
|
|
<control channel="2">
|
|
<type>VELOCITY</type>
|
|
<offset>0</offset>
|
|
<p_gain>0.20</p_gain>
|
|
<i_gain>0</i_gain>
|
|
<d_gain>0</d_gain>
|
|
<i_max>0</i_max>
|
|
<i_min>0</i_min>
|
|
<cmd_max>2.5</cmd_max>
|
|
<cmd_min>-2.5</cmd_min>
|
|
<jointName>iris::rotor_2_joint</jointName>
|
|
<multiplier>-838</multiplier>
|
|
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
|
|
</control>
|
|
<control channel="3">
|
|
<type>VELOCITY</type>
|
|
<offset>0</offset>
|
|
<p_gain>0.20</p_gain>
|
|
<i_gain>0</i_gain>
|
|
<d_gain>0</d_gain>
|
|
<i_max>0</i_max>
|
|
<i_min>0</i_min>
|
|
<cmd_max>2.5</cmd_max>
|
|
<cmd_min>-2.5</cmd_min>
|
|
<jointName>iris::rotor_3_joint</jointName>
|
|
<multiplier>-838</multiplier>
|
|
<controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
|
|
</control>
|
|
</plugin>
|
|
|
|
</model>
|
|
</sdf>
|