Module/GPS UBlox UCenter

From PaparazziUAV
Jump to navigation Jump to search
The printable version is no longer supported and may have rendering errors. Please update your browser bookmarks and please use the default browser print function instead.

If you use a µ-blox GPS without flash memory, this module will take over the task of initializing the GPS for you when you power your autopilot.

It has auto-baudrate to detect the current GPS baudrate, and configures all message rates and communication ports. The module will send a DEBUG message (ID 26) that indicates the firmware version in your GPS, the previous baudrate, and the reply for each configuration step. To enable and view the message, you will need to define DEBUG_GPS_UBX_UCENTER as TRUE in your airframe configuration file. See the example below for more details.

It will configure the following settings:

  • set baudrate to GPS_BAUD (typically either 38400 or 57600)
  • enable the NAV_POSLLH, NAV_VELNED, NAV_STATUS, NAV_SVINFO, NAV_SOL
  • disable UTM on old Lea4P by not sending NAV_POSUTM
  • enable SBAS
  • configure it to 3D only fix
  • set the internal dynamic model to Airborne 2G


Basic

Add the gps_ubx_ucenter module to the "modules" section in your aircraft configuration file:

File: conf/airframes/myplane.xml
  <modules>
    ...
    <load name="gps_ubx_ucenter.xml"/>
  </modules>


Advanced

You can specify to a different dynamic model for the u-blox.

File: conf/airframes/myplane.xml
  <modules>
    ...
    <load name="gps_ubx_ucenter.xml">
	<define name="GPS_UBX_NAV5_DYNAMICS" value="NAV5_DYN_PORTABLE" />
    </load>
  </modules>

Additional details on GPS_UBX_NAV5_DYNAMICS

The ublox GPS uses a dynamics model (motion model) to filter the noisy GPS readings and produce smoother results. The dynamics model will affect what positions and speeds are accurately tracked by GPS. Generally, it is recommend to use NAV5_DYN_PORTABLE for quadcopters and NAV5_DYN_AIRBORNE_2G for fixed wings.

The follow is taken from the ublox protocol specification document:

u-blox positioning technology supports different dynamic platform models to adjust the navigation engine to the expected application environment. These platform settings can be changed dynamically without performing a power cycle or reset. The settings improve the receiver's interpretation of the measurements and thus provide a more accurate position output. Setting the receiver to an unsuitable platform model for the given application environment results in a loss of receiver performance and position accuracy.

Dynamic Platform Model
NAV5_DYN_PORTABLE Applications with low acceleration, e.g. portable devices. Suitable for most situations. MAX Altitude [m]: 12000, MAX Velocity [m/s]: 310, MAX Vertical Velocity [m/s]: 50, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium
NAV5_DYN_STATIONARY Used in timing applications (antenna must be stationary) or other stationary applications. Velocity restricted to 0 m/s. Zero dynamics assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 10, MAX Vertical Velocity [m/s]: 6, Sanity check type: Altitude and Velocity, Max Position Deviation: Small
NAV5_DYN_PEDESTRIAN Applications with low acceleration and speed, e.g. how a pedestrian would move. Low acceleration assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 30, MAX Vertical Velocity [m/s]: 20, Sanity check type: Altitude and Velocity, Max Position Deviation: Small
NAV5_DYN_AUTOMOTIVE Used for applications with equivalent dynamics to those of a passenger car. Low vertical acceleration assumed. MAX Altitude [m]: 6000 (5000 for firmware versions 6.00 and below), MAX Velocity [m/s]: 84 (62 for firmware versions 4.00 to 5.00), MAX Vertical Velocity [m/s]: 15, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium
NAV5_DYN_SEA Recommended for applications at sea, with zero vertical velocity. Zero vertical velocity assumed. Sea level assumed. MAX Altitude [m]: 500, MAX Velocity [m/s]: 25, MAX Vertical Velocity [m/s]: 5, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium
NAV5_DYN_AIRBORNE_1G Used for applications with a higher dynamic range and vertical acceleration than a passenger car. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 100, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
NAV5_DYN_AIRBORNE_2G Recommended for typical airborne environment. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 250, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
NAV5_DYN_AIRBORNE_4G Only recommended for extremely dynamic environments. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 500, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large

Debug

You can specify to receive a DEBUG message over telemetry by enabling it in your airframe file:

File: conf/airframes/myplane.xml
  <modules>
    ...
    <load name="gps_ubx_ucenter.xml">
	<define name="GPS_UBX_NAV5_DYNAMICS" value="NAV5_DYN_PORTABLE" />
	<define name="DEBUG_GPS_UBX_UCENTER" value="TRUE" />
    </load>
  </modules>

The DEBUG message has the following information:

  • [0] Initial baudrate high
  • [1] Initial baudrate low. For example if the baud rate is 9600 you will see 9,6
  • [2] ublox software verision high
  • [3] ublox software version low
  • [4] ublox hardware version high
  • [5] ublox hardware version low
  • [6] Always 0
  • [7] Success of setting CFG-NAV5. For all of these a value of 0 indicates no response, 1 is success and 2 is command rejected by GPS.
  • [8] Success of enable NAV-POSLLH
  • [9] Success of enable NAV-VELNED
  • [10] Success of enable NAV-STATUS
  • [11] Success of enable NAV-SVINFO
  • [12] Success of enable NAV-SOL
  • [13] Success of disabling NAV-POSUTM (typically fails to 0 for non LEA-4P modules)
  • [14] Success of enable SBAS
  • [15] Success of setting CFG-RATE
  • [16] Success of setting RXM-RAW (typically disabled - see USE_GPS_UBX_RXM_RAW flag to enable)
  • [17] Success of setting RXM-SFRB (typically disabled - see USE_GPS_UBX_RXM_SFRB flag to enable)
  • [18] Success of saving configuration to ublox memory

The debug message is sent only once a few seconds after powering on. Make sure to have messages displayed before powering on to make sure to capture it. If you get all zeroes then check cabling and try again. Make sure RX from the GPS is connected to TX on the autopilot.