Files
paparazzi/conf/joystick/radiomaster_TX16s.xml
T
Christophe De Wagter cf7c8b3797
Issues due date / Add labels to issues (push) Has been cancelled
Doxygen / build (push) Has been cancelled
MAVLab Course2026 Updates (p1) (#3632)
* updated distance measurement script.
- automatically shows which ids are available
- filter out big jumps
- plot_summary.py shows distance over time with recording regions

* Adding config file for radiomaster pocket joystick ble/usb (#108)

* added radiomaster tx16s xml (#123)

Co-authored-by: Wiebe van der Knaap <wkvanderknaap@tudelft.nl>

* Fix joystick device argument parsed as single token in control panel sessions (#118)

The `-d 0` joystick device flag was passed as a single `flag` attribute,
causing the joystick program to receive it as one token instead of two
separate arguments. This prevented the device number from being recognized,
breaking joystick input in the Simulation - Gazebo and Flight UDP sessions.

Fixed by splitting into `<arg flag="-d" constant="0"/>`.

Co-authored-by: Claude Sonnet 4.6 <noreply@anthropic.com>

* fixed names of variables and resolution bugs, added documentation (#113)

Co-authored-by: macoman <macoman@student.tudelft.nl>

* Update Gazebo Models: Gate, Plants, Logo

* Added some (math) tests (#114)

* added a test for paparazzi's math librarie's int sqrt function and int quaternion normalization function
* Keep essential tests

Reduced the number of tests planned from 9 to 6 and removed tests for int32_sqrt.

---------

Co-authored-by: LSSchef <l.s.scheffer@student.tudelft.nl>
Co-authored-by: AniketBehura <aniketbehura1023@gmail.com>
Co-authored-by: diaa <D.abbasi@student.tudelft.nl>

* Feat: readme update for submodule installation (#115)

* feat: readme update for submodule installation

* Rename README to README.md

---------

Co-authored-by: Christophe De Wagter <dewagter@gmail.com>

---------

Co-authored-by: robinferede <robinferede@tudelft.nl>
Co-authored-by: Robin Euger <robin.euger@gmail.com>
Co-authored-by: Wiebe van der Knaap <wkvanderknaap@tudelft.nl>
Co-authored-by: EAbbenhuis <113993394+EAbbenhuis@users.noreply.github.com>
Co-authored-by: Claude Sonnet 4.6 <noreply@anthropic.com>
Co-authored-by: Mihai Coman <127535163+miki133@users.noreply.github.com>
Co-authored-by: macoman <macoman@student.tudelft.nl>
Co-authored-by: Swayam Kuckreja <110131770+swayamkuckreja@users.noreply.github.com>
Co-authored-by: LSSchef <l.s.scheffer@student.tudelft.nl>
Co-authored-by: AniketBehura <aniketbehura1023@gmail.com>
Co-authored-by: diaa <D.abbasi@student.tudelft.nl>
Co-authored-by: Douwe-Rijs <Douwe@standofl.nl>
2026-04-09 15:37:28 +02:00

63 lines
2.2 KiB
XML

<joystick>
<!--
RadioMaster TX16S (OpenTX/EdgeTX) — Paparazzi UAV joystick configuration
Axis mapping (verify with: ./sw/ground_segment/joystick/test_stick):
Axis 0 : Roll — right stick X
Axis 1 : Pitch — right stick Y
Axis 2 : Throttle — left stick Y
Axis 3 : Yaw — left stick X
Axis 5 : Mode switch — 3-position (SA/SB): low / mid / high
Axis 6 : Arm switch — 2-position (SF/SE): 0 = disarm, ~1024 = arm
TX16S switch axes output 0 / ~1024 / ~2047 (unsigned), which input2ivy
scales to -127 / 0 / +127 internally.
Pitch and throttle are inverted relative to Paparazzi convention — hence
the minus signs in the RC_UP field values below.
-->
<input>
<!-- deadband: eliminates stick drift at centre (range 0-127) -->
<!-- exponent: finer control near centre, faster at extremes (range 0-1.0) -->
<axis index="0" name="roll" deadband="10" exponent="0.5" limit="1.0" trim="0"/>
<axis index="1" name="pitch" deadband="10" exponent="0.5" limit="1.0" trim="0"/>
<axis index="2" name="throttle" deadband="5" exponent="0.0" limit="1.0" trim="0"/>
<axis index="3" name="yaw" deadband="10" exponent="0.5" limit="1.0" trim="0"/>
<axis index="5" name="mode_sw"/>
<axis index="6" name="arm_sw"/>
</input>
<variables>
<var name="mode" default="0"/>
</variables>
<messages period="0.05">
<message class="datalink" name="RC_UP" send_always="true">
<field name="channels"
value="roll;
-pitch;
yaw;
Fit(-throttle,-127,127,0,127);
Fit(mode_sw,-127,127,0,2)"/>
</message>
<!-- Arm switch: arm_sw > -60 = armed, arm_sw < -60 = disarmed/killed -->
<message class="ground" name="DL_SETTING"
on_event="arm_sw &gt; -60">
<field name="index" value="IndexOfSetting('autopilot.kill_throttle')"/>
<field name="value" value="0"/>
</message>
<message class="ground" name="DL_SETTING"
on_event="arm_sw &lt; -60">
<field name="index" value="IndexOfSetting('autopilot.kill_throttle')"/>
<field name="value" value="1"/>
</message>
</messages>
</joystick>