[modules] Removed GPS_PORT_ID, added comments, and compile warnings if GPS_PORT_ID is defined.

closes #653
closes #647
This commit is contained in:
Andrew Chambers
2014-02-28 08:48:23 -08:00
committed by Felix Ruess
parent b5bbd5b987
commit a0bc3a70e7
8 changed files with 247 additions and 113 deletions
+1 -3
View File
@@ -160,9 +160,7 @@
<define name="CHIMU_BIG_ENDIAN" />
</load>
<load name="cam_point.xml" />
<load name="gps_ubx_ucenter.xml">
<define name="GPS_PORT_ID" value="GPS_PORT_UART2" />
</load>
<load name="gps_ubx_ucenter.xml"/>
</modules>
<firmware name="fixedwing">
@@ -169,7 +169,6 @@ ap.CFLAGS += -DMODEM_BAUD=B57600
ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_MODEL_H=\"subsystems/radio_control/spektrum_dx7eu.h\"
ap.CFLAGS += -DGPS_USE_LATLONG
ap.CFLAGS += -DGPS_PORT_ID=GPS_PORT_UART1
include $(PAPARAZZI_SRC)/conf/firmwares/booz2_common.makefile
include $(CFG_BOOZ)/booz2_autopilot.makefile
-1
View File
@@ -16,7 +16,6 @@
<makefile target="ap">
<file name="gps_i2c.c"/>
<define name="GPS_CONFIGURE" />
<define name="GPS_PORT_ID" value="GPS_PORT_DDC"/>
</makefile>
</module>
+4 -6
View File
@@ -10,14 +10,12 @@ Automatically configure any Ublox GPS for paparazzi.
- configures all the messages, and the rates
- automatic baudrate detection
Warning: you still need to tell the driver
1. Which paparazzi uart you use
2. Inside the ublox gps there are also many ports.
The tiny/ppzgps use ublox_internal_port1 (UART1) but if for instance you use a LS-SAM
or I2C device you need to set this by defining GPS_PORT_ID.
Warning: you still need to tell the driver, which paparazzi port you use.
</description>
<define name="GPS_PORT_ID" value="GPS_PORT_UART1" description="Port inside the Ublox GPS (GPS_PORT_DDC, GPS_PORT_UART1, GPS_PORT_UART2, GPS_PORT_USB, GPS_PORT_SPI)"/>
<define name="GPS_UBX_UCENTER_RATE" value="250" description="Data output rate in ms"/>
<define name="GPS_UBX_NAV5_DYNAMICS"
value="NAV5_DYN_PORTABLE|NAV5_DYN_FIXED|NAV5_DYN_STATIONARY|NAV5_DYN_PEDESTRIAN|NAV5_DYN_AUTOMOTIVE|NAV5_DYN_SEA|NAV5_DYN_AIRBORNE_1G|NAV5_DYN_AIRBORNE_2G|NAV5_DYN_AIRBORNE_4G"
description="Dynamic model used by ublox GPS filter. Default:NAV5_DYN_AIRBORNE_2G"/>
<define name="USE_GPS_UBX_RXM_RAW" description="Activate raw measurments (only available on U-Blox T versions)"/>
</doc>
<header>
+11
View File
@@ -114,6 +114,9 @@
</block>
</message>
<message name="PRT_POLL" ID="0x00" length="0">
</message>
<message name="MSG" ID="0x01" length="3">
<field name="Class" format="U1"/>
<field name="MsgId" format="U1"/>
@@ -207,6 +210,14 @@
<class name="RXM" ID="0x02">
<!--
Only available with raw data product variant.
This message contains all information needed to be able to generate a RINEX observation
file.
This message outputs pseudorange, doppler and carrier phase measurements for GPS
satellites once signals have been synchronised. No other GNSS types are currently
supported.
-->
<message name="RAW" ID="0x10">
<field name="iTOW" format="I4" unit="ms"/>
<field name="week" format="I2" unit="weeks"/>
+182 -57
View File
@@ -29,6 +29,8 @@
#include "gps_ubx_ucenter.h"
#include "subsystems/gps/gps_ubx.h"
#include "subsystems/datalink/downlink.h"
#include <stdio.h>
//////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////
@@ -46,6 +48,7 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr);
#define GPS_UBX_UCENTER_REPLY_ACK 1
#define GPS_UBX_UCENTER_REPLY_NACK 2
#define GPS_UBX_UCENTER_REPLY_VERSION 3
#define GPS_UBX_UCENTER_REPLY_CFG_PRT 4
// All U-Center data
struct gps_ubx_ucenter_struct gps_ubx_ucenter;
@@ -93,6 +96,16 @@ void gps_ubx_ucenter_periodic(void)
{
gps_ubx_ucenter.status = GPS_UBX_UCENTER_STATUS_CONFIG;
gps_ubx_ucenter.cnt = 0;
#if DEBUG_GPS_UBX_UCENTER
if (gps_ubx_ucenter.baud_init > 0)
{
printf("Initial ublox baudrate found: %u\n", gps_ubx_ucenter.baud_init);
}
else
{
printf("WARNING: Unable to determine the ublox baudrate. Autoconfiguration is unlikely to work.\n");
}
#endif
}
else
{
@@ -129,17 +142,23 @@ void gps_ubx_ucenter_event(void)
return;
// Read Configuration Reply's
if (gps_ubx.msg_class == UBX_ACK_ID) {
switch (gps_ubx.msg_class)
{
case UBX_ACK_ID:
if (gps_ubx.msg_id == UBX_ACK_ACK_ID) {
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_ACK;
#if DEBUG_GPS_UBX_UCENTER
printf("ACK\n");
#endif
}
else
{
else {
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NACK;
#if DEBUG_GPS_UBX_UCENTER
printf("NACK\n");
#endif
}
}
// Version info
else if (gps_ubx.msg_class == UBX_MON_ID) {
break;
case UBX_MON_ID:
if (gps_ubx.msg_id == UBX_MON_VER_ID ) {
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_VERSION;
gps_ubx_ucenter.sw_ver_h = UBX_MON_VER_c(gps_ubx.msg_buf,0) - '0';
@@ -149,7 +168,23 @@ void gps_ubx_ucenter_event(void)
gps_ubx_ucenter.hw_ver_h += 10*(UBX_MON_VER_c(gps_ubx.msg_buf,32) - '0');
gps_ubx_ucenter.hw_ver_l = UBX_MON_VER_c(gps_ubx.msg_buf,37) - '0';
gps_ubx_ucenter.hw_ver_l += 10*(UBX_MON_VER_c(gps_ubx.msg_buf,36) - '0');
#if DEBUG_GPS_UBX_UCENTER
printf("ublox sw_ver: %u.%u\n", gps_ubx_ucenter.sw_ver_h, gps_ubx_ucenter.sw_ver_l);
printf("ublox hw_ver: %u.%u\n", gps_ubx_ucenter.hw_ver_h, gps_ubx_ucenter.hw_ver_l);
#endif
}
break;
case UBX_CFG_ID:
if (gps_ubx.msg_id == UBX_CFG_PRT_ID) {
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_CFG_PRT;
gps_ubx_ucenter.port_id = UBX_CFG_PRT_PortId(gps_ubx.msg_buf,0);
gps_ubx_ucenter.baud_run = UBX_CFG_PRT_Baudrate(gps_ubx.msg_buf,0);
#if DEBUG_GPS_UBX_UCENTER
printf("gps_ubx_ucenter.baud_run: %u\n", gps_ubx_ucenter.baud_run);
printf("gps_ubx_ucenter.port_id: %u\n", gps_ubx_ucenter.port_id);
#endif
}
break;
}
}
@@ -159,7 +194,18 @@ void gps_ubx_ucenter_event(void)
// UCENTER Configuration Functions
/**
* Enable u-blox message at desired rate (Hz). Will enable the message on the port
* Polls the u-blox port configuration
* When the payload is omitted (zero length), the configuration for the incoming
* (currently used) port is reported.
*
*/
static inline void gps_ubx_ucenter_config_port_poll(void)
{
UbxSend_CFG_PRT_POLL();
}
/**
* Enable u-blox message at desired period. Will enable the message on the port
* that this command is received on. For example, sending this configuration message
* over UART1 will cause the desired message to be published on UART1.
*
@@ -168,13 +214,21 @@ void gps_ubx_ucenter_event(void)
*
* @param class u-blox message class
* @param id u-blox message ID
* @param rate Desired rate in cycles per second (Hz)
* @param rate Desired period to send message. Example: Setting 3 would send the message on every 3rd navigation solution.
*/
static inline void gps_ubx_ucenter_enable_msg(uint8_t class, uint8_t id, uint8_t rate)
{
UbxSend_CFG_MSG(class, id, rate);
}
/**
* Automatically determine the baudrate of the u-blox module.
* Only needed when connecting to a UART port on the u-blox.
* The discovered baudrate is copied to gps_ubx_ucenter.baud_init.
*
* @param nr Autobaud step number to perform
* @return FALSE when completed
*/
static bool_t gps_ubx_ucenter_autobaud(uint8_t nr)
{
switch (nr)
@@ -187,48 +241,58 @@ static bool_t gps_ubx_ucenter_autobaud(uint8_t nr)
case 2:
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
GpsUartSetBaudrate(B38400); // Try the most common first?
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_VELNED_ID, 1);
gps_ubx_ucenter_config_port_poll();
break;
case 3:
if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK)
{
gps_ubx_ucenter.baud_init = 38400;
gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run;
return FALSE;
}
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
GpsUartSetBaudrate(B9600); // Maybe the factory default?
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_VELNED_ID, 1);
gps_ubx_ucenter_config_port_poll();
break;
case 4:
if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK)
{
gps_ubx_ucenter.baud_init = 9600;
gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run;
return FALSE;
}
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
GpsUartSetBaudrate(B57600); // The high-rate default?
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_VELNED_ID, 1);
gps_ubx_ucenter_config_port_poll();
break;
case 5:
if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK)
{
gps_ubx_ucenter.baud_init = 57600;
gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run;
return FALSE;
}
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
GpsUartSetBaudrate(B4800); // Default NMEA baudrate finally?
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_VELNED_ID, 1);
GpsUartSetBaudrate(B4800); // Default NMEA baudrate?
gps_ubx_ucenter_config_port_poll();
break;
case 6:
if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK)
{
gps_ubx_ucenter.baud_init = 4800;
gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run;
return FALSE;
}
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
GpsUartSetBaudrate(B115200); // Last possible option for ublox
gps_ubx_ucenter_config_port_poll();
break;
case 7:
if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK)
{
gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run;
return FALSE;
}
// Autoconfig Failed... let's setup the failsafe baudrate
// Should we try even a different baudrate?
gps_ubx_ucenter.baud_init = 0;
gps_ubx_ucenter.baud_init = 0; // Set as zero to indicate that we couldn't verify the baudrate
GpsUartSetBaudrate(B9600);
return FALSE;
default:
@@ -245,22 +309,35 @@ static bool_t gps_ubx_ucenter_autobaud(uint8_t nr)
#define NAV_DYN_AUTOMOTIVE 3
#define NAV_DYN_SEA 4
#define NAV_DYN_AIRBORNE_1G 5
#define NAV_DYN_AIRBORNE_2G 6
#define NAV_DYN_AIRBORNE_2G 6 // paparazzi default
#define NAV_DYN_AIRBORNE_4G 7
#define NAV5_DYN_PORTABLE 0
#define NAV5_DYN_PORTABLE 0 // ublox default
#define NAV5_DYN_FIXED 1
#define NAV5_DYN_STATIONARY 2
#define NAV5_DYN_PEDESTRIAN 3
#define NAV5_DYN_AUTOMOTIVE 4
#define NAV5_DYN_SEA 5
#define NAV5_DYN_AIRBORNE_1G 6
#define NAV5_DYN_AIRBORNE_2G 7
#define NAV5_DYN_AIRBORNE_2G 7 // paparazzi default
#define NAV5_DYN_AIRBORNE_4G 8
#ifndef GPS_UBX_NAV5_DYNAMICS
#define GPS_UBX_NAV5_DYNAMICS NAV5_DYN_AIRBORNE_2G
#endif
#define NAV5_MASK 0x05 // Apply dynamic model and position fix mode settings
#define NAV5_2D_ONLY 1
#define NAV5_3D_ONLY 2
#define NAV5_AUTO 3
#define NAV5_3D_ONLY 2 // paparazzi default
#define NAV5_AUTO 3 // ublox default
#define NAV5_DEFAULT_MIN_ELEV 5 // deg
#define NAV5_DEFAULT_PDOP_MASK 25 // no units
#define NAV5_DEFAULT_TDOP_MASK 25 // no units
#define NAV5_DEFAULT_P_ACC 100 // m
#define NAV5_DEFAULT_T_ACC 300 // m
#define NAV5_DEFAULT_STATIC_HOLD_THRES 0 // cm/s
#define IGNORED 0
#define RESERVED 0
@@ -274,7 +351,9 @@ static inline void gps_ubx_ucenter_config_nav(void)
}
else
{
UbxSend_CFG_NAV5(0x05, NAV5_DYN_AIRBORNE_2G, NAV5_3D_ONLY, IGNORED, IGNORED, IGNORED, IGNORED, IGNORED, IGNORED, IGNORED, IGNORED, IGNORED, RESERVED, RESERVED, RESERVED, RESERVED);
UbxSend_CFG_NAV5(NAV5_MASK, GPS_UBX_NAV5_DYNAMICS, NAV5_3D_ONLY, IGNORED, IGNORED, NAV5_DEFAULT_MIN_ELEV, RESERVED,
NAV5_DEFAULT_PDOP_MASK, NAV5_DEFAULT_TDOP_MASK, NAV5_DEFAULT_P_ACC, NAV5_DEFAULT_T_ACC,
NAV5_DEFAULT_STATIC_HOLD_THRES, RESERVED, RESERVED, RESERVED, RESERVED);
}
}
@@ -283,6 +362,13 @@ static inline void gps_ubx_ucenter_config_nav(void)
/////////////////////////////////////
// UBlox port and protocol GPS configuration
#ifdef GPS_PORT_ID
#warning "GPS_PORT_ID is no longer needed by the ublox ucenter for automatically configuration. Please remove this defined variable and double check that autoconfig is working as expected."
#endif
// UART mode: 8N1 with reserved1 set for compatability with A4
#define UBX_UART_MODE_MASK 0x000008D0
#define UBX_PROTO_MASK 0x0001
#define NMEA_PROTO_MASK 0x0002
#define RTCM_PROTO_MASK 0x0004
@@ -292,32 +378,44 @@ static inline void gps_ubx_ucenter_config_nav(void)
#define GPS_PORT_UART2 0x02
#define GPS_PORT_USB 0x03
#define GPS_PORT_SPI 0x04
#ifndef GPS_PORT_ID
#define GPS_PORT_ID GPS_PORT_UART1
#endif
#define GPS_PORT_RESERVED 0x05
#define __UBX_GPS_BAUD(_u) _u##_BAUD
#define _UBX_GPS_BAUD(_u) __UBX_GPS_BAUD(_u)
#define UBX_GPS_BAUD _UBX_GPS_BAUD(GPS_LINK)
#ifndef GPS_UBX_UCENTER_RATE
#define GPS_UBX_UCENTER_RATE 0x00FA
#define GPS_UBX_UCENTER_RATE 0x00FA // In milliseconds. 0x00FA = 250ms = 4Hz
#endif
static inline void gps_ubx_ucenter_config_port(void)
{
switch(gps_ubx_ucenter.port_id)
{
// I2C Interface
#if GPS_PORT_ID == GPS_PORT_DDC
UbxSend_CFG_PRT(GPS_PORT_ID, 0x0, 0x0, GPS_I2C_SLAVE_ADDR, 0x0, UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
case GPS_PORT_DDC:
#ifdef GPS_I2C
UbxSend_CFG_PRT(gps_ubx_ucenter.port_id, 0x0, 0x0, GPS_I2C_SLAVE_ADDR, 0x0, UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
#else
printf("WARNING: Please include the gps_i2c module.\n");
#endif
break;
// UART Interface
#if GPS_PORT_ID == GPS_PORT_UART1 || GPS_PORT_ID == GPS_PORT_UART2
UbxSend_CFG_PRT(GPS_PORT_ID, 0x0, 0x0, 0x000008D0, UART_SPEED(UBX_GPS_BAUD), UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
#endif
#if GPS_PORT_ID == GPS_PORT_USB
UbxSend_CFG_PRT(GPS_PORT_ID, 0x0, 0x0, 0x0, 0, UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
#endif
case GPS_PORT_UART1:
case GPS_PORT_UART2:
UbxSend_CFG_PRT(gps_ubx_ucenter.port_id, 0x0, 0x0, UBX_UART_MODE_MASK, UART_SPEED(UBX_GPS_BAUD), UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
break;
// USB Interface
case GPS_PORT_USB:
UbxSend_CFG_PRT(gps_ubx_ucenter.port_id, 0x0, 0x0, 0x0, 0x0, UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
break;
case GPS_PORT_SPI:
printf("WARNING: ublox SPI port is currently not supported.\n");
break;
default:
printf("WARNING: Unknown ublox port id: %u\n", gps_ubx_ucenter.port_id);
break;
}
}
#define GPS_SBAS_ENABLED 0x01
@@ -326,38 +424,59 @@ static inline void gps_ubx_ucenter_config_port(void)
#define GPS_SBAS_CORRECTIONS 0x02
#define GPS_SBAS_INTEGRITY 0x04
#define GPS_SBAS_MAX_SBAS 1 // Default ublox setting uses 3 SBAS channels(?)
#define GPS_SBAS_AUTOSCAN 0x00
static inline void gps_ubx_ucenter_config_sbas(void)
{
// Since March 2nd 2011 EGNOS is released for aviation purposes
const uint8_t nrofsat = 1;
UbxSend_CFG_SBAS(GPS_SBAS_ENABLED, GPS_SBAS_RANGING | GPS_SBAS_CORRECTIONS | GPS_SBAS_INTEGRITY, nrofsat, 0x00, 0x00);
UbxSend_CFG_SBAS(GPS_SBAS_ENABLED, GPS_SBAS_RANGING | GPS_SBAS_CORRECTIONS | GPS_SBAS_INTEGRITY, GPS_SBAS_MAX_SBAS, GPS_SBAS_AUTOSCAN, GPS_SBAS_AUTOSCAN);
//UbxSend_CFG_SBAS(0x00, 0x00, 0x00, 0x00, 0x00);
}
// Text Telemetry for Debugging
#undef GOT_PAYLOAD
#include "subsystems/datalink/downlink.h"
static bool_t gps_ubx_ucenter_configure(uint8_t nr)
{
#if DEBUG_GPS_UBX_UCENTER
printf("gps_ubx_ucenter_configure nr: %u\n",nr);
#endif
// Store the reply of the last configuration step and reset
if (nr < GPS_UBX_UCENTER_CONFIG_STEPS)
gps_ubx_ucenter.replies[nr] = gps_ubx_ucenter.reply;
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
switch (nr) {
case 0:
UbxSend_MON_GET_VER();
// Use old baudrate to issue a baudrate change command
gps_ubx_ucenter_config_port();
break;
case 1:
#if DEBUG_GPS_UBX_UCENTER
if (gps_ubx_ucenter.reply != GPS_UBX_UCENTER_REPLY_ACK)
{
printf("ublox did not acknowledge port configuration.\n");
}
else
{
printf("Changed ublox baudrate to: %u\n", UART_SPEED(UBX_GPS_BAUD));
}
#endif
// Now the GPS baudrate should have changed
GpsUartSetBaudrate(UBX_GPS_BAUD);
gps_ubx_ucenter.baud_run = UART_SPEED(UBX_GPS_BAUD);
UbxSend_MON_GET_VER();
break;
case 2:
case 3:
case 4:
// UBX_G5010 takes 0.7 seconds to answer a firmware request
// Version info is important for porper configuration as different firmwares have different settings
break;
case 5:
// UBX_G5010 takes 0.7 seconds to answer a firmware request
// Version info is important for proper configuration as different firmwares have different settings
break;
case 6:
// Send some debugging info: detected baudrate, software version etc...
gps_ubx_ucenter.replies[0] = (gps_ubx_ucenter.baud_init/1000);
gps_ubx_ucenter.replies[1] = (gps_ubx_ucenter.baud_init - 1000 * gps_ubx_ucenter.replies[0]) / 100;
@@ -368,32 +487,27 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr)
#if DEBUG_GPS_UBX_UCENTER
DOWNLINK_SEND_DEBUG(DefaultChannel, DefaultDevice,6,gps_ubx_ucenter.replies);
#endif
//////////////////////////////////
// Actual configuration start
// Use old baudrate to issue a baudrate change command
gps_ubx_ucenter_config_port();
break;
case 6:
// Now the GPS baudrate should have changed
GpsUartSetBaudrate(UBX_GPS_BAUD);
gps_ubx_ucenter.baud_run = UART_SPEED(UBX_GPS_BAUD);
// Configure CFG-NAV(5) message
gps_ubx_ucenter_config_nav();
break;
case 7:
// Geodetic Position Solution
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_POSLLH_ID,1);
break;
case 8:
// Velocity Solution in NED
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_VELNED_ID, 1);
break;
case 9:
// Receiver Navigation Status
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_STATUS_ID, 1);
break;
case 10:
// Space Vehicle Information
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_SVINFO_ID, 4);
break;
case 11:
// Navigation Solution Information
#if GPS_UBX_UCENTER_SLOW_NAV_SOL
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_SOL_ID, 8);
#else
@@ -405,17 +519,21 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr)
gps_ubx_ucenter_enable_msg(UBX_NAV_ID, UBX_NAV_POSUTM_ID, 0);
break;
case 13:
// SBAS Configuration
gps_ubx_ucenter_config_sbas();
break;
case 14:
// Poll Navigation/Measurement Rate Settings
UbxSend_CFG_RATE(GPS_UBX_UCENTER_RATE, 0x0001, 0x0000);
break;
case 15:
// Raw Measurement Data
#if USE_GPS_UBX_RXM_RAW
gps_ubx_ucenter_enable_msg(UBX_RXM_ID, UBX_RXM_RAW_ID, 1);
#endif
break;
case 16:
// Subframe Buffer
#if USE_GPS_UBX_RXM_SFRB
gps_ubx_ucenter_enable_msg(UBX_RXM_ID, UBX_RXM_SFRB_ID, 1);
#endif
@@ -427,11 +545,18 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr)
case 18:
#if DEBUG_GPS_UBX_UCENTER
// Debug Downlink the result of all configuration steps: see messages
// To view, enable DEBUG message in your telemetry configuration .xml
DOWNLINK_SEND_DEBUG(DefaultChannel, DefaultDevice,GPS_UBX_UCENTER_CONFIG_STEPS,gps_ubx_ucenter.replies);
for (int i = 0; i < GPS_UBX_UCENTER_CONFIG_STEPS; i++)
{
printf("%u\n", gps_ubx_ucenter.replies[i]);
}
#endif
return FALSE;
default:
break;
}
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE;
return TRUE; // Continue, except for the last case
}
+5 -2
View File
@@ -39,8 +39,8 @@ struct gps_ubx_ucenter_struct
uint8_t reply;
uint8_t cnt;
uint32_t baud_init;
uint32_t baud_run;
uint32_t baud_init; // Initial baudrate of the ublox module
uint32_t baud_run; // Current baudrate of the ublox module
uint8_t sw_ver_h;
uint8_t sw_ver_l;
@@ -48,6 +48,9 @@ struct gps_ubx_ucenter_struct
uint16_t hw_ver_h;
uint16_t hw_ver_l;
/// Port identifier number
uint8_t port_id;
char replies[GPS_UBX_UCENTER_CONFIG_STEPS];
};
+1
View File
@@ -25,6 +25,7 @@
#include "std.h"
/// Default address for u-blox (and others?)
#define GPS_I2C_SLAVE_ADDR (0x42 << 1)
#define GPS_I2C_BUF_SIZE 256