Joystick to MSP Interface - samdrew/betaflight_gazebo GitHub Wiki

There is a useful Github Gist provided by cs8425 (Youtube), who has been posting resources for this use-case for longer than most others.

My fork is available here, which changes the channel mappings to match Betaflight default, and updates the joystick input device. Download or clone (git clone https://gist.github.com/628efd4113b8f65ce7d6d75bc2275444.git) the gist, and we can get it running.

Setting up MSP-Node

Note, ordering is important. It must be

  1. Configured correctly, with dependencies
  2. Controller connected
  3. Betaflight SITL running and configured
  4. Executed

Configuration should only be required once, while the other requirements will be necessary every time this is run.

Configuration

Start by renaming the directory to something useful

mv 628efd4113b8f65ce7d6d75bc2275444 msp-node

Next, we need to confirm what the controller input will be. Type ls /dev/input/js*. This will likely return 0 or 1 result (using Ubuntu in Parallels, I get one result). If you already have a single joystick listed then the configuration should be correct.

If you get zero results (ie "ls: cannot access '/dev/input/js*': No such file or directory") then it is necessary to edit emu-dx6-msp.js line 144 (vi emu-dx6-msp.js +144, or your preferred editor), to change the joystick id from 1 to 0.

The last point of configuration in emu-dx6-msp.js is if you are running it on a different machine from your Betaflight SITL, the IP address and port of the UART2 interface on the Betaflight SITL instance can be configured at the top of the file.

Finally ensure you have NodeJS installed

sudo apt update
sudo apt install nodejs

Running the script at this point will result in an error due to an unconnected controller, but demonstrates that the script executes.

$ node emu-dx6-msp.js
node:events:495
      throw er; // Unhandled 'error' event
      ^

Controller Connected

Connect your USB HID Controller to your computer and ensure that it has USB Passthrough enabled to your VM running the msp-node script. Verify that it has succeeded by checking for an additional js device listed under /dev/inputs/.

Controller Connection (Detailed)

Using a RadioMaster TX16 MKII running EdgeTX and similar devices, connecting the controller to a VM can also be fiddly, so the following is a step-by-step guide that avoids the normal issues.

  1. Power on controller
  2. Connect USB-C cable to port on top of Controller
  3. Connect the controller to your Mac via a USB-A port (The controller does not recognise USB-C to USB-C connections). This means you will have to use a USB Hub or a USB-A to USB-C dongle attached to your computer.
  4. Select USB Joystick (HID) device on your Controller interface.
  5. Configure passthrough of the device to the correct VM. In Parallels the following window comes up

This should now be listed as an additional device under /dev/inputs/ for your VM.

Betaflight SITL

Ensure that Betaflight SITL is running and configured according to this page. When starting Betaflight the output should be similar to the following:

$ ./obj/main/betaflight_SITL.elf
[SITL] The SITL will output to IP 127.0.0.1:9002 (Gazebo) and 127.0.0.1:9001 (RealFlightBridge)
[system]Init...
[SITL] init PwmOut UDP link to gazebo 127.0.0.1:9002...0
[SITL] init PwmOut UDP link to RF9 127.0.0.1:9001...0
[SITL] start UDP server @9003...0
[SITL] start UDP server for RC input @9004...0
[FLASH_Unlock] loaded 'eeprom.bin', size = 32768 / 32768
[timer]Init...
Initialized motor count 4
bind port 5761 for UART1
bind port 5762 for UART2
debugInit
unusedPinsInit

The important item in this list is bind port 5762 for UART2, meaning it is ready to accept the controller input over the network port.

Execution

Now that the controller is connected, and Betaflight SITL is running, you can start the script.

node emu-dx6-msp.js

The output will show a long list of arrays, containing the input values for the various channels supported. Move your controller input to see the values update.

[
  1500,
  1500,
  1000.0076295109484,
  1500,
  1000.0076295109484,
  1000.0076295109484,
  1100,
  1100,
  undefined: 1000.0076295109484
]

If this works and has successfully connected to Betaflight, the terminal running Betaflight should show the new log messages

New connection on UART2, 0
[NEW]UART2: 1,1

Finally check that this is being received by the SITL FC, by connecting with the configurator and going to the Receiver page. The input sliders should respond to your controller, and the Preview screen embedded should move the simulated drone accordingly.

Troubleshooting

Betaflight SITL isn't heavily used by the wider community, as people working with automation more often rely upon automation-first flight control software (Ardupilot and PX4). As such the SITL module doesn't always behave as expected.

Motors Missing

Going to the motors tab on the Configurator will sometimes say "Quad X model requires 4 motors resources...". If this is happening, restart the SITL script. If it persists try a Save and Restart.

Receiver Not Responding

Sometimes, despite the connection between the msp-node script and Betaflight SITL being successful (New connection on UART2, 0 in Betaflight console output), the Receiver input does not respond. In this case it is also worth testing using the Radio Emulator option on that page. When the Emulator is opened and enabled, the inputs sliders should respond to the movement of the red dots representing the flight sticks, as well as the aux controls.

If this isn't working it demonstrates that the issue is absolutely limited to Betaflight SITL configuration. Change the Receiver Mode from MSP to any of the other options, before changing it back to MSP and taking the Save and Reboot option. Hopefully this will fix the issue.