Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/autotest/aircraft/arducopter/plus_quad2.xml
Views: 2010
<?xml version="1.0"?>1<?xml-stylesheet type="text/xsl" href="http://jsbsim.sourceforge.net/JSBSim.xsl"?>2<fdm_config xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" name="dflyer" version="2.0" release="ALPHA" xsi:noNamespaceSchemaLocation="http://jsbsim.sourceforge.net/JSBSim.xsd">3<fileheader>4<author> James Goppert </author>5<filecreationdate> 2010-03-11 </filecreationdate>6<version>0.0 </version>7<description> Arducopter DIY Drones UAV. </description>8</fileheader>9<metrics>10<wingarea unit="M2"> 0.017</wingarea>11<wingspan unit="M"> 0.13 </wingspan>12<chord unit="FT"> 0.0 </chord>13<htailarea unit="FT2"> 0.0 </htailarea>14<htailarm unit="FT"> 0.0 </htailarm>15<vtailarea unit="FT2"> 0.0 </vtailarea>16<vtailarm unit="FT"> 0.0 </vtailarm>17<location name="AERORP" unit="IN">18<x> 0.00 </x>19<y> 0.00 </y>20<z> 0.00 </z>21</location>22<location name="EYEPOINT" unit="IN">23<x> 0.0 </x>24<y> 0.0 </y>25<z> 0.0 </z>26</location>27<location name="VRP" unit="IN">28<x>0</x>29<y>0</y>30<z>0</z>31</location>32</metrics>33<mass_balance>34<!--roughtly approximating this as a solid sphere with correct mass-->35<ixx unit="KG*M2"> 0.036 </ixx>36<iyy unit="KG*M2"> 0.036 </iyy>37<izz unit="KG*M2"> 0.036 </izz>38<emptywt unit="KG"> 1.0 </emptywt>39<location name="CG" unit="IN">40<x> 0.0 </x>41<y> 0.0 </y>42<z> 0.0 </z>43</location>44<pointmass name="Payload">45<weight unit="KG"> 0.0 </weight>46<location unit="IN">47<x> 0.0 </x>48<y> 0.0 </y>49<z> 0.0 </z>50</location>51</pointmass>52</mass_balance>53<ground_reactions>54<contact type="BOGEY" name="frontbase">55<location unit="M">56<x> -0.283 </x>57<y> 0.00 </y>58<z> -0.033</z>59</location>60<static_friction> 0.80 </static_friction>61<dynamic_friction> 0.50 </dynamic_friction>62<spring_coeff unit="N/M"> 800 </spring_coeff>63<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>64<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>65</contact>66<contact type="BOGEY" name="rearbase">67<location unit="M">68<x> 0.283 </x>69<y> 0.00 </y>70<z> -0.033</z>71</location>72<static_friction> 0.80 </static_friction>73<dynamic_friction> 0.50 </dynamic_friction>74<spring_coeff unit="N/M"> 800 </spring_coeff>75<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>76<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>77</contact>78<contact type="BOGEY" name="leftbase">79<location unit="M">80<x> 0.00 </x>81<y> 0.283 </y>82<z> -0.033</z>83</location>84<static_friction> 0.80 </static_friction>85<dynamic_friction> 0.50 </dynamic_friction>86<spring_coeff unit="N/M"> 800 </spring_coeff>87<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>88<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>89</contact>90<contact type="BOGEY" name="rightbase">91<location unit="M">92<x> 0.00 </x>93<y> -0.283 </y>94<z> -0.033</z>95</location>96<static_friction> 0.80 </static_friction>97<dynamic_friction> 0.50 </dynamic_friction>98<spring_coeff unit="N/M"> 800 </spring_coeff>99<damping_coeff unit="N/M2/SEC2" type="SQUARE"> 7 </damping_coeff>100<damping_coeff_rebound unit="N/M2/SEC2" type="SQUARE"> 300 </damping_coeff_rebound>101</contact>102</ground_reactions>103<!-- the front and rear motors spin clockwise, and the left and right motors spin counter-clockwise. -->104<propulsion>105<engine file="a2830-12" name="front">106<location unit="M">107<x> -0.283 </x>108<y> 0.00 </y>109<z> 0.00 </z>110</location>111<orient unit="DEG">112<pitch> 90.00 </pitch>113<roll> 0.00 </roll>114<yaw> 0.00 </yaw>115</orient>116<feed>0</feed>117<thruster file="prop10x4.5">118<location unit="M">119<x> -0.283 </x>120<y> 0.00 </y>121<z> 0.125 </z>122</location>123<orient unit="DEG">124<pitch> 90.00 </pitch>125<roll> 0.00 </roll>126<yaw> 0.00 </yaw>127</orient>128<sense> 1 </sense>129<p_factor> 10 </p_factor>130</thruster>131</engine>132<engine file="a2830-12" name="rear">133<location unit="M">134<x> 0.283 </x>135<y> 0.000 </y>136<z> 0.000 </z>137</location>138<orient unit="DEG">139<pitch> 90.00 </pitch>140<roll> 0.00 </roll>141<yaw> 0.00 </yaw>142</orient>143<feed>0</feed>144<thruster file="prop10x4.5">145<location unit="M">146<x> 0.283 </x>147<y> 0.000 </y>148<z> 0.125 </z>149</location>150<orient unit="DEG">151<pitch> 90.00 </pitch>152<roll> 0.00 </roll>153<yaw> 0.00 </yaw>154</orient>155<sense> 1 </sense>156<p_factor> 10 </p_factor>157</thruster>158</engine>159<engine file="a2830-12" name="left">160<location unit="M">161<x> 0.00 </x>162<y> 0.283 </y>163<z> 0.00 </z>164</location>165<orient unit="DEG">166<pitch> 90.00 </pitch>167<roll> 0.00 </roll>168<yaw> 0.00 </yaw>169</orient>170<feed>0</feed>171<thruster file="prop10x4.5">172<location unit="M">173<x> 0.00 </x>174<y> 0.283 </y>175<z> 0.125 </z>176</location>177<orient unit="DEG">178<pitch> 90.00 </pitch>179<roll> 0.00 </roll>180<yaw> 0.00 </yaw>181</orient>182<sense> -1 </sense>183<p_factor> 10 </p_factor>184</thruster>185</engine>186<engine file="a2830-12" name="right">187<location unit="M">188<x> 0.000 </x>189<y> -0.283 </y>190<z> 0.000 </z>191</location>192<orient unit="DEG">193<pitch> 90.00 </pitch>194<roll> 0.00 </roll>195<yaw> 0.00 </yaw>196</orient>197<feed>0</feed>198<thruster file="prop10x4.5">199<location unit="M">200<x> 0.000 </x>201<y> -0.283 </y>202<z> 0.125 </z>203</location>204<orient unit="DEG">205<pitch> 90.00 </pitch>206<roll> 0.00 </roll>207<yaw> 0.00 </yaw>208</orient>209<sense> -1 </sense>210<p_factor> 10 </p_factor>211</thruster>212</engine>213<tank type="FUEL" number="0">214<location unit="M">215<x> 0.00 </x>216<y> 0.00 </y>217<z> -0.07 </z>218</location>219<!--have to have a fuel capacity, so setting it small-->220<capacity unit="KG"> 0.00000000001 </capacity>221<contents unit="KG"> 0.0 </contents>222</tank>223</propulsion>224<aerodynamics>225<axis name="LIFT">226</axis>227<axis name="DRAG">228<function name="aero/coefficient/CD0">229<description>Overall Drag</description>230<product>231<property>aero/qbar-psf</property>232<property>metrics/Sw-sqft</property>233<value>1</value>234</product>235</function>236</axis>237<axis name="SIDE">238</axis>239<axis name="ROLL">240</axis>241<axis name="PITCH">242</axis>243<axis name="YAW">244</axis>245</aerodynamics>246</fdm_config>247<!-- vim:ts=2:sw=2:expandtab -->248249250