GPS fixes : reporting 3D DGPS fixes and teaching users

1,092 views
Skip to first unread message

Olivier ADLER

unread,
Jun 21, 2013, 8:13:44 AM6/21/13
to drones-...@googlegroups.com


I think that it would be desirable to report 3D DGPS fixes through Mavling, so that users can know if SBAS corrections have been applied before to take off.

Actually i think that there is no way to know something about that, without connecting the GPS to the U-Blox U-center PC software.


Depending on the SBAS satellites position above the horizon, acquisition can be more difficult than classical satellites, and because of the low bitrate, a DGPS fix can ask from a couple minutes to 5 minutes or more.

More the DGPS corrections are not backed up through power off / power on in the GPS module. So after each battery change, a new DGPS acquisition needs to be redone from start.


SBAS is a good way to have a more reliable GPS position, with a guaranteed precision of 7.60 meters and GPS integrity detection reported in less than 6.2 seconds.


We are still seeing users flying between buildings at low altitude and expecting good GPS precision in those difficult conditions.


Because the 3.0 firmware has a firs class navigation code, with perfect precision and higher speed / acceleration settings, i feel that for version 3.0 release we should direct users to the GPS Wiki pages

http://copter.ardupilot.com/wiki/common-gps-how-it-works/
http://copter.ardupilot.com/wiki/gps-failsafe/


They are explaining the basis of GPS.



Olivier.


Doug

unread,
Jun 22, 2013, 10:21:21 PM6/22/13
to drones-...@googlegroups.com
Oliver, 
The u-blox NAV-SBAS message outputs the status of the SBAS sub system.  Users would need to enable it (in existing modules) and the driver would need to be modified to parse this message.  Also if you are looking for a single SBAS on/off indication it may be more involved.  I have not looked at this but the ublox may apply corrections for some number of satellites less than the full number being tracked if information for some but not all satellites has been received.  If this is the case then an additional message might need to be parsed to be able to cross check the satellites in use with the satellites with SBAS corrections.  

In any case it is do-able without needing anything unusual (e.g. connecting to u-center).

Doug

Olivier ADLER

unread,
Jun 23, 2013, 5:38:36 AM6/23/13
to drones-...@googlegroups.com

Thanks, Doug.

According to the tests i did with U-center, it seems to me that 3D DGPS fix indication (a 3D fix with SBAS corrections in it) is set when SBAS corrections have been received for all satellites.

Depending about the SBAS integrity detection setting, some satellites could be removed from the solution, but that is independent.

At the same time as the 3D DGPS fix indication, we can see a "D" appearing in all the satellites reception level bargraph, meaning that a differential correction has been applied.

I will look in the LEA6 manual to see if there is a simple message to report a DGPS fix.


Olivier.

Mark Colwell

unread,
Jun 23, 2013, 9:35:39 AM6/23/13
to drones-...@googlegroups.com
DGPS fix is available in NAV-STATUS message, if DGPS is lost a position spike is generated. 
Be aware that we are sending PDOP not HDOP to APM. I have enabled NAV-DOP and added decoding of DGPS Fix (boolean) message in NAV-Status (added to auto config also). It now can send correct data for HDOP. only adds 26 bytes sent over Mavlink.
I use uCenter to preload A/E satellite position data to GPS using 7day option (GPS must have backup battery connected to keep data while GPS is disconnected) 

in AP_GPS_UBLOX.ccp

case MSG_DOP: // add for true HDOP mjc

Debug("MSG_DOP h_dop=%u h_dop=%u", _buffer.buffer.dop.horizontal_DOP);

p_dop = _buffer.dop.positional_DOP; //mjc for HK_GCS note re-named positional_DOP with extra "al"

h_dop = _buffer.dop.horizontal_DOP; //mjc for HK_GCS

v_dop = _buffer.dop.vertical_DOP; //mjc for MAVLINK_GCS

break;

    case MSG_SOL:

        Debug("MSG_SOL fix_status=%u fix_type=%u",

              _buffer.solution.fix_status,

              _buffer.solution.fix_type);

        next_fix        = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);

        if (!next_fix) {

            fix = false;

        }

        num_sats        = _buffer.solution.satellites;

        hdop            = _buffer.solution.position_DOP; // s/b pdop = _buffer.solution.position_DOP see MSG_DOP

        break;


 


--
You received this message because you are subscribed to the Google Groups "drones-discuss" group.
To unsubscribe from this group and stop receiving emails from it, send an email to drones-discus...@googlegroups.com.
For more options, visit https://groups.google.com/groups/opt_out.
 
 

Mark Colwell

unread,
Jun 23, 2013, 9:44:13 AM6/23/13
to drones-...@googlegroups.com
in AP_GPS_UBLOX.h

    struct ubx_nav_status {

        uint32_t time;                                  // GPS msToW

        uint8_t fix_type;

        uint8_t fix_status;

        uint8_t differential_status;    // logic AND with fix type to display 3D/DGPS Fix status mjc

        uint8_t res;

        uint32_t time_to_first_fix;

        uint32_t uptime;                                // milliseconds

    };

struct ubx_nav_dop { // added new DOP message for for GCS mjc

uint32_t time; // GPS msToW NOT sent mjc

uint16_t geometric_DOP; // g_dop  NOT sent mjc

uint16_t positional_DOP; // p_dop sent to GCS Note: New name positional_DOP with extra "al"  mjc

uint16_t time_DOP; // t_dop  NOT sent mjc    

uint16_t vertical_DOP; // v_dop sent to GCS  mjc

uint16_t horizontal_DOP; // h_dop sent to GCS Note: actual H_dop value when using UBLOX_DL mjc

uint16_t northing_DOP; // n_dop  NOT sent mjc

uint16_t easting_DOP; // e_dop  NOT sent mjc

};

Olivier ADLER

unread,
Jun 23, 2013, 10:24:17 AM6/23/13
to drones-...@googlegroups.com

Thanks Mark for those fast fixes.

Concerning DGPS fix lost, i remember that there is a timeout setting in the LEA6, and it's default is 1 minute if i'm right.

Perhaps we should rise this timeout value because the most important for us is to avoid relative position jumps during fly ? Absolute positioning is not so important for us.


Olivier.

Mark Colwell

unread,
Jun 23, 2013, 12:22:57 PM6/23/13
to drones-...@googlegroups.com
my attempt at Mavlink message GPS_LOCK  (ID 15) fails CRC.  I hand built this but it needs to get generated by a message_definition.

          <message id="15" name="GPS_LOCK">

               <description>GPS lock quality, (with NAV-DOP message enabled on ublox) DOP dilution of position values as returned by the Global Positioning System (GPS). This is a RAW sensor value. See message GLOBAL_POSITION for full position data.</description>

               <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>

               <field type="uint8_t" name="fix_type">0-1: NO fix, 2: 2D fix, 3: 3D fix, 4: 3D/DGPS fix, 5: Time only fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>

               <field type="uint8_t" name="num_sats">Satellites used for fix</field>

               <field type="uint8_t" name="dgps_fix">DGPS fix 1= ON  0= Waiting/OFF</field>

               <field type="int16_t" name="h_dop">GPS H_DOP</field>

               <field type="int16_t" name="v_dop">GPS V_DOP</field>

               <field type="int16_t" name="p_dop">GPS P_DOP</field>

          </message>


mavlink_msg_gps_lock.h
Reply all
Reply to author
Forward
0 new messages