ardupilot/Tools/autotest/aircraft/arducopter/Engines/prop10x4.5.xml

77 lines
2.0 KiB
XML
Raw Normal View History

<?xml version="1.0"?>
<!-- Generated by Aero-Matic v 1.1
Inputs:
horsepower: 0.250767
pitch: fixed
max engine rpm: 9435
prop diameter (ft): 0.83333333333333
Outputs:
max prop rpm: 22515.60
gear ratio: 0.42
Cp0: 0.002731
Ct0: 0.003823
static thrust (lbs): 0.66
-->
<propeller name="prop">
<!--<ixx> 0.00 </ixx>-->
<ixx> 0.000041666666 </ixx>
<!--assuming solid rod of mass 8 g-->
<diameter unit="IN"> 10.0 </diameter>
<numblades> 2 </numblades>
<gearratio> 1.0 </gearratio>
<p_factor> 0.79 </p_factor>
<table name="C_THRUST" type="internal">
<tableData><!--experimentally measured-->
0.0 0.0054513
1.4 0.0054513
<!--aeromatic generated-->
<!--0.0 0.0042-->
<!--0.1 0.0040-->
<!--0.2 0.0038-->
<!--0.3 0.0035-->
<!--0.4 0.0032-->
<!--0.5 0.0028-->
<!--0.6 0.0023-->
<!--0.7 0.0017-->
<!--0.8 0.0009-->
<!--1.0 -0.0003-->
<!--1.2 -0.0016-->
<!--1.4 -0.0030-->
</tableData>
</table>
<table name="C_POWER" type="internal">
<tableData>
0.0 0.0028
0.1 0.0028
0.2 0.0027
0.3 0.0027
0.4 0.0025
0.5 0.0023
0.6 0.0021
0.7 0.0018
0.8 0.0015
1.0 0.0005
1.2 -0.0008
1.4 -0.0025
1.6 -0.0042
</tableData>
</table>
<!-- thrust effects of helical tip Mach -->
<table name="CT_MACH" type="internal">
<tableData>
0.85 1.0
1.05 0.8
</tableData>
</table>
<!-- power-required effects of helical tip Mach -->
<table name="CP_MACH" type="internal">
<tableData>
0.85 1.0
1.05 1.8
2.00 1.4
</tableData>
</table>
</propeller>