<xml> <object name="ManualControlSettings" singleinstance="true" settings="true"> <description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description> <field name="InputMode" units="" type="enum" elements="1" options="PWM,PPM,Spektrum" defaultvalue="PWM"/> <field name="Roll" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="Channel1"/> <field name="Pitch" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="Channel2"/> <field name="Yaw" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="Channel3"/> <field name="Throttle" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="Channel4"/> <field name="FlightMode" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="Channel5"/> <field name="Accessory1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/> <field name="Accessory2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/> <field name="Accessory3" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,None" defaultvalue="None"/> <field name="Arming" units="" type="enum" elements="1" options="Channel1,Channel1_Rev,Channel2,Channel2_Rev,Channel3,Channel3_Rev,Channel4,Channel4_Rev,Channel5,Channel5_Rev,Channel6,Channel6_Rev,Channel7,Channel7_Rev,Channel8,Channel8_Rev,None" defaultvalue="Channel1"/> <field name="Pos1StabilizationSettings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude" defaultvalue="Attitude"/> <field name="Pos2StabilizationSettings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude" defaultvalue="Attitude"/> <field name="Pos3StabilizationSettings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude" defaultvalue="Attitude"/> <field name="Pos1FlightMode" units="" type="enum" elements="1" options="Manual,Stabilized,Auto" defaultvalue="Manual"/> <field name="Pos2FlightMode" units="" type="enum" elements="1" options="Manual,Stabilized,Auto" defaultvalue="Stabilized"/> <field name="Pos3FlightMode" units="" type="enum" elements="1" options="Manual,Stabilized,Auto" defaultvalue="Auto"/> <field name="ChannelMax" units="us" type="int16" elements="8" defaultvalue="2000"/> <field name="ChannelNeutral" units="us" type="int16" elements="8" defaultvalue="1500"/> <field name="ChannelMin" units="us" type="int16" elements="8" defaultvalue="1000"/> <field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/> <access gcs="readwrite" flight="readwrite"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetryflight acked="true" updatemode="onchange" period="0"/> <logging updatemode="never" period="0"/> </object> </xml>