Testing Your App

Android App

Android Emulator

In order for the Android emulator in Android Studio to receive the MAVLink UDP messages from the simulation, we need to redirect the UDP port between the host and the emulator.

The port forwarding can be set using telnet:

telnet localhost 5554

 

In another terminal, get the auth token by doing:

cat ~/.emulator_console_auth_token

 

Copy the token and use it to authenticate the telnet session:

auth <paste your token>

 

Then, set up the redirect:

redir add udp:14540:14540

 

Android Device

By default, the simulator will only try to connect to localhost and not to another device.

To connect to your device, use either of the two options:

  1. Broadcasting
    • This option doesn't require the IP address of the Android device, but any applications or devices listening for MAVLink messages, i.e. QGroundControl, could potentially connect before your device and intercept your messages.
    • Start the PX4 simulator and type the following in the pxh>:

      param set MAV_BROADCAST 1
      param save

      Open Set IP configuration options

       

  2. Specify device IP

    • This option avoids a race condition for the client connection.

    • Before starting the PX4 simulator, open the file wherever/Firmware/posix-configs/SITL/init/lpe/typhoon_h480 (use iris for jMAVSim) and look for this line:

      mavlink start -u 14557 -r 4000000 -m custom -o 14540

      then add the IP of the Android device in the local network with the -t option:

      mavlink start -u 14557 -r 4000000 -m custom -o 14540 -t 192.168.0.X

       

iOS App

iOS Emulator

If the iOS simulator runs on the same computer as the SITL simulation, it should automatically connect.

iOS Device (iPad/iPhone)

By default, the SITL simulation will only try to connect on localhost, but not to an iPhone/iPad on the network.

To connect to your device, use either of the two options:

  1. Broadcasting
    • This option doesn't require the IP address of the iOS device, but any applications or devices listening for MAVLink messages, i.e. QGroundControl, could potentially connect before your device and intercept your messages.
    • Start the PX4 simulator and type the following in the pxh>:

      param set MAV_BROADCAST 1
      param save

       

      Open Set IP configuration options

  2. Specify device IP

    • This option avoids a race condition for the client connection.

    • Before starting the PX4 simulator, open the file wherever/Firmware/posix-configs/SITL/init/lpe/typhoon_h480 (use iris for jMAVSim) and look for this line:

      mavlink start -u 14557 -r 4000000 -m custom -o 14540

      then add the IP of the iOS device in the local network with the -t option:

      mavlink start -u 14557 -r 4000000 -m custom -o 14540 -t 192.168.0.X