Skip to content

Commit

Permalink
AP_GPS: add support for setting the default Ublox baudrate
Browse files Browse the repository at this point in the history
  • Loading branch information
bugobliterator committed May 15, 2024
1 parent 5bbfbad commit d94e3dd
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,13 +72,21 @@ extern const AP_HAL::HAL &hal;

// baudrates to try to detect GPSes with
const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U, 460800U};

#ifndef AP_GPS_UBLOX_DEFAULT_BAUDRATE
#define AP_GPS_UBLOX_DEFAULT_BAUDRATE 230400
#endif
// initialisation blobs to send to the GPS to try to get it into the
// right mode.
const char AP_GPS::_initialisation_blob[] =
#if AP_GPS_UBLOX_ENABLED
#if AP_GPS_UBLOX_DEFAULT_BAUDRATE == 115200
UBLOX_SET_BINARY_115200
#elif AP_GPS_UBLOX_DEFAULT_BAUDRATE == 460800
UBLOX_SET_BINARY_460800
#else
UBLOX_SET_BINARY_230400
#endif
#endif
#if AP_GPS_SIRF_ENABLED
SIRF_SET_BINARY
#endif
Expand Down

0 comments on commit d94e3dd

Please sign in to comment.