Pozyx for Non-GPS Navigation

This article explains how a Pozyx system based on the DWM1000 can be used as a short-range substitute for a GPS allowing position control modes like Loiter, PosHold, RTL, Auto indoors.

Required Hardware

Placing the anchors

The anchors should be placed in a rectangular shape. The anchor with the lowest ID (IDs are printed in hexidecimal on each device) will act as the “origin” and should be placed at the lower-left corner of the rectangle. Each of the remaining three anchors should be placed in a corner so that the anchor IDs increase as you travel an “N” pattern within the rectangle. The configuration is slightly simpler if the line from the origin anchor to the 2nd anchor is due North but it is not required as the BCN_ORIENT_YAW parameter can be used to account this difference.

../_images/pozyx-anchor-layout.png

Preparing the tag

../_images/pozy-pixhawk-uno.png
  • connect one of the autopilot’s telemetry connections to the UNO. Telem1 is shown above but any SERIAL port will work equally well.

  • autopilot’s UART port GND should be connected to one of the UNO’s GND pins.

  • autopilot’s UART port TX should be connected to the UNO’s pin 10.

  • autopilot’s UART port RX should be connected to the UNO’s pin 11.

  • autopilot’s UART port VCC may be connected to the UNO’s 5V connector to provide power to the Uno/Pozyx from the autopilot.

The Arduino IDE should be used to load IndoorLoiter sketch onto the Uno after first changing the anchor tags found here to match the IDs of the tags in your setup.

At this point you may wish to test the tag’s ability to communicate with the tags by:

  • powering on all the anchors.

  • connect the UNO’s Type B USB to your PC.

  • connect with the Arduino IDE’s serial monitor (set to baud 115200) and check no “Beacon Configuration failed” messages appear. If they do, check that the IDs have been set correctly in the IndoorLoiter2.ino sketch (above).

Mount the Pozyx tag on the top of the Arduino Uno and then mount on the vehicle.

Configuration through the Ground Station

Connect with a Ground Station and set the following parameters:

  • set BCN_TYPE to 1 (means using Pozyx system)

  • set BCN_LATITUDE, BCN_LONGITUDE and BCN_ALT to match your actual location. Getting these values exactly correct is not particularly important although getting it close is required in order for the compass’s declination to be correctly looked up from the small database held within ArduPilot.

  • set BCN_ORIENT_YAW to the heading from the origin anchor to the 2nd anchor. One way to capture this value is to stand at the origin holding the vehicle so that its nose points towards the second beacon. Read the vehicle’s heading from the HUD and enter this value into BCN_ORIENT_YAW

  • set EK3_SRC1_POSXY to 4 (Beacon)

  • set EK3_SRC1_VELXY to 0 (None)

  • set EK3_SRC1_VELZ to 0 (None)

  • set EK3_SRC1_POSZ to 4 (Beacon)

  • set EK3_SRC1_YAW to 1 (Compass) since a compass is required for use with this device.

  • set ARMING_CHECK to -9 to disable the GPS arming check

  • set SERIAL1_BAUD to 115 to set SERIAL1 port’s baud rate to 115200 (if using a different SERIAL port set its baud rate to 115, instead)

  • set SERIAL1_PROTOCOL to 13 (Beacon) to enable reading the IndoorLoiter2 protocol (If using a different port, set its protocol to 13 instead)

  • set BRD_SER1_RTSCTS to 0 to ensure telem1 does not use flow control (If using Telem2 set BRD_SER2_RTSCTS instead, not required if using a SERIAL port without flow control)

Ground Testing

  • Connect the Autopilot to a ground station. You may need to connect the Lipo battery as well because some computers are unable to provide enough power through their USB port for the combined autopilot+Pozyx+Uno.

  • Press the UNO’s white or red reset button which can be found next to the USB port (see image above)

  • After about 1 minute the vehicle’s position should jump to the lattitude, longitude you input during the configuration step (above). If it does not, connect a USB cable to the UNO’s USB port and open the Arduino IDE’s serial monitor and look for errors.

  • Check that the vehicle’s position is relatively stable (i.e. moving around less than one meter)

  • Walk the vehicle around between the anchors and ensure that its position on the map updates correctly

Flight testing

Setup the transmitter with Stabilize, AltHold and Loiter flight modes. Take off in AltHold mode and maintain a stable hover. Switch to Loiter but be ready to switch back to AltHold or Stabilize if the vehicle’s position or altitude becomes unstable.

DataFlash logging

The distance to the beacons can be found in the dataflash log’s BCN message’s D0, D1, D2, D3 fields.

User videos