Csr location class shows location and satellite information, which supports H13467 + ST F103RB/NXP LCP1549 boards now.

Dependents:   CsrLocationDemo CsrLocationDemo

Fork of CsrLocation by jie zhao

CsrLocation.h

Committer:
zhjcpi
Date:
2014-11-19
Revision:
19:27aa296d2ea1
Parent:
18:5d72465991f5

File content as of revision 19:27aa296d2ea1:

/* CSRLocation class for mbed Microcontroller
 * Copyright 2014 CSR plc
 */

#ifndef CSRLOCATION_H
#define CSRLOCATION_H

#include <GPSProviderImplBase.h>

#define CSR_LOC_SDK_VER                 "CSR-LOC-SDK-0.5"

typedef uint16_t CsrResult;
#define CSR_RESULT_SUCCESS  ((CsrResult) 0x0000)
#define CSR_RESULT_FAILURE  ((CsrResult) 0xFFFF)

/* Time related definitions */
#define CSR_ULOC_UTC_GPS_OFFSET_MS      ((uint64_t)(315964800000LL))
#define CSR_ULOC_SEC_IN_WEEK_MS         (604800000)
#define CSR_ULOC_UTC_LEAP_OFFSET_MS     (15000)


/* IOCTL commands */
#define CSR_IOCTL_CMD_WAKEUP_STATUS     (0x01)
#define CSR_IOCTL_CMD_ONOFF_ON          (0x02)
#define CSR_IOCTL_CMD_ONOFF_OFF         (0x03)
#define CSR_IOCTL_CMD_ONOFF_PULSE       (0x04)
#define CSR_IOCTL_CMD_RESET_ON          (0x05)
#define CSR_IOCTL_CMD_RESET_OFF         (0x06)
#define CSR_IOCTL_CMD_PROTO_NMEA        (0x07)
#define CSR_IOCTL_CMD_PROTO_OSP         (0x08)


/* OSP protocol related definitions */
#define MAX_VERSION_LENGTH 80

/* OSP message header */
#define OSP_MSG_HEAD0                   (0xA0)
#define OSP_MSG_HEAD1                   (0xA2)
/* OSP message footer */
#define OSP_MSG_TAIL0                   (0xB0)
#define OSP_MSG_TAIL1                   (0xB3)

/* NMEA message header */
#define NMEA_MSG_HEAD0                  ('$')
#define NMEA_MSG_HEAD1                  ('G')
/* NMEA message footer */
#define NMEA_MSG_TAIL0                  ('*')

#define CSR_SWAPIN16(bytestream) (((uint16_t)*((bytestream) + 0) << 8) | ((uint16_t)*((bytestream) + 1)))

#define CSR_SWAPIN32(bytestream)             \
    (((uint32_t)*((bytestream) + 0) << 24)   \
     | ((uint32_t)*((bytestream) + 1) << 16) \
     | ((uint32_t)*((bytestream) + 2) << 8)  \
     | ((uint32_t)*((bytestream) + 3)))


/* import macros for little endian: */
/* NOTE: must use {} around these macros when calling in a loop */
#define BINARY_IMPORT_UINT8(bytestream) (*((bytestream)++))
#define BINARY_IMPORT_UINT16(bytestream) ((uint16_t) CSR_SWAPIN16((bytestream))); bytestream += 2
#define BINARY_IMPORT_UINT32(bytestream) ((uint32_t) CSR_SWAPIN32((bytestream))); bytestream += 4
#define BINARY_IMPORT_SINT32(bytestream) ((int32_t)  CSR_SWAPIN32((bytestream))); bytestream += 4

#define OSP_MAKE_MSG_ID(mid, sid) ((((mid) & 0xFF) << 8) | ((sid) & 0xFF))

#define OSP_MSG_SW_VERSION              OSP_MAKE_MSG_ID(0x06, 0x0)
#define OSP_MSG_OK_TO_SEND              OSP_MAKE_MSG_ID(0x12, 0x0)
#define OSP_MSG_GEODETIC_NAVIGATION     OSP_MAKE_MSG_ID(0x29, 0x0)
#define OSP_MSG_MULTI_CONSTELLATION     OSP_MAKE_MSG_ID(0x43, 0x0)
    #define OSP_MSG_GNSS_NAV_DATA       OSP_MAKE_MSG_ID(0x43, 0x01)
    #define OSP_MSG_GNSS_SAT_DATA       OSP_MAKE_MSG_ID(0x43, 0x10)
#define OSP_MSG_HW_CONFIG_REQ           OSP_MAKE_MSG_ID(0x47, 0x0)
#define OSP_MSG_PWR_MODE_RSP            OSP_MAKE_MSG_ID(0x5A, 0x0)
    #define OSP_MSG_PWR_MODE_FPM_RSP    OSP_MAKE_MSG_ID(0x5A, 0x0)
    #define OSP_MSG_PWR_MODE_LPM_RSP    OSP_MAKE_MSG_ID(0x5A, 0x6)


#define GNSS_SAT_DATA_NUM_OF_SATS       (15)
#define CODEC_GLO_MAX_CHANNELS          (14)
/* The end of OSP protocol definitions */


#define LOC_MAX_GNSS_SVS                (32)
#define LOC_GLO_FREQ_OFFSET             (77)
#define LOC_GLO_FREQ_ID_START           (70)
#define LOC_GLO_FREQ_ID_END             (83)
#define LOC_NUM_OF_GLO_FREQ_CHANNELS    (1 + LOC_GLO_FREQ_ID_END - LOC_GLO_FREQ_ID_START)

#define MAX_PORT_NUM_STRING_LENGTH      (16)
#define MAX_SERIAL_BUF_LEN              (2048)
#define MAX_SERIAL_PKT_LEN              (512)

#define BAUDRATE_NMEA                   4800
#define BAUDRATE_OSP                    115200

#define PROTO_CHECK_TIMEOUT             (2.0)

/** Indicates the outputted location information */
#define LOC_OUTPUT_LOCATION             (1)
/* Indicates the outputted sv status information */
#define LOC_OUTPUT_SV_STATUS            (2)
#define LOC_OUTPUT_NMEA                 (3)

#if 0
#define CSR_LOG_INFO    printf
#else
#define CSR_LOG_INFO(...) {                             \
        if (pSerialDebug != NULL) {                     \
            (pSerialDebug->printf(__VA_ARGS__));        \
        }                                               \
    }
#endif // if 0

/** Location event definitions */
typedef enum {
    /** Start result event */
    CSR_LOC_EVENT_START_RESULT,
    /** Stop result event */
    CSR_LOC_EVENT_STOP_RESULT,
} eCsrLocEventType;

/** Power mode selection */
typedef enum {
    /** full power mode */
    PWR_FULL,
    /** Low power push to fix mode */
    PWR_PTF,
} ePowerMode;

/** Power mode selection */
typedef enum {
    /** NMEA protocol */
    PROTO_NMEA,
    /** OSP protocol */
    PROTO_OSP,
} eProto;

/* Protocol detection state */
typedef enum {
    STATE_START1,       /* Indicates the first byte of the OSP or NMEA message header*/
    STATE_START2,       /* Indicates the second byte of the OSP or NMEA message header */
    STATE_SIZE1,        /* Indicates the first byte of the OSP message length */
    STATE_SIZE2,        /* Indicates the second byte of the OSP message length  */
    STATE_PAYLOAD,      /* Indicates the start of payload of the OSP message */
    STATE_CHECKSUM1,    /* Indicates the first byte of the OSP message checksum  */
    STATE_CHECKSUM2,    /* Indicates the second byte of the OSP message checksum  */
    STATE_END1,         /* Indicates the first byte of the OSP or NMEA message footer  */
    STATE_END2          /* Indicates the second byte of the OSP message footer  */
} eProtoDetState;

/* CSR Location state */
typedef enum {
    CSR_LOC_STATE_IDLE,
    CSR_LOC_STATE_RUN,
} eCsrLocState;

/* Location chip protocol detection state */
typedef enum {
    PROTO_STATE_DET_INVALID = 0,
    PROTO_STATE_DET_OSP,
    PROTO_STATE_DET_NMEA,
    //   PROTO_STATE_SWI_OSP_FROM_NMEA,
    PROTO_STATE_DET_OSP_FROM_NMEA,
    //   PROTO_STATE_SWI_NMEA_FROM_OSP,
    PROTO_STATE_DET_NMEA_FROM_OSP,
    PROTO_STATE_DET_OK,
} eProtoState;

/* Location chip status */
typedef enum {
    /* Location chip is going to hibernation mode and cannot accept message any more */
    ENGINE_STATUS_NOTOK2SEND,
    /* Location come back from hibernation mode and can accept message now */
    ENGINE_STATUS_OK2SEND
} eEngineStatus;

/* OSP data type to be sent to location chip */
typedef enum {
    SEND_DATA_TYPE_OSP_STOP_REQ,
    SEND_DATA_TYPE_OSP_VER_REQ,
    SEND_DATA_TYPE_OSP_LPM_REQ,
    SEND_DATA_TYPE_OSP_FPM_REQ,
    SEND_DATA_TYPE_OSP_SWITCH2NMEA_REQ,
    SEND_DATA_TYPE_NMEA_SWITCH2OSP_REQ,
    SEND_DATA_TYPE_NMEA_STOP_REQ
} eSendDataType;

typedef struct GpsTime {
    /** Week part of GPS time */
    uint16_t gps_week;
    /** Time of second part of GPS time in millisecond */
    uint32_t tow;
} tGpsTime;

/** Structure to hold Position Response Message Information. */
typedef struct LocPosResp {
    tGpsTime gpsTime; /** gps time */
    uint64_t utcTime; /** UTC time in millisecond */
    /** Latitude */
    double lat;
    /** Longitude */
    double lon;
    /** Altitude */
    double alt;
} tLocPosResp;

/** Structure to hold Satellite Information. */
typedef struct LocSvInfo {
    /** Prn or svId */
    uint8_t  prn;
    /** The ratio of carrier and noise */
    float    cno;
    /** elevation */
    float    elevation;
    /** azimuth */
    float    azimuth;
    /** satellite state */
    uint16_t state;
} tLocSvInfo;

/** Structure to hold Satellite Information for GLONASS */
typedef struct LocGloSvInfo {
    /** Prn or svId */
    uint8_t  prn;
    /** Slot number */
    uint8_t  sno;
    /** The ratio of carrier and noise */
    float    cno;
    /** elevation */
    float    elevation;
    /** azimuth */
    float    azimuth;
    /** satellite state */
    uint16_t state;
} tLocGloSvInfo;

/** Structure to hold Satellite Status Information. */
typedef struct LocSvStatus {
    /** Week part of GPS time */
    uint16_t      gps_week;
    /** Time of second part of GPS time */
    uint32_t      tow;
    /** Time of millisecond part of GPS time */
    uint32_t      tow_sub_ms;

    /**Number of GPS SVs currently visible **/
    uint8_t       numOfSVs;
    /**Number of GLONASS SVs currently visible **/
    uint8_t       numOfGloSVs;
    /** GPS SVs information */
    tLocSvInfo    svList[LOC_MAX_GNSS_SVS];
    /** GLONASS SVs information */
    tLocGloSvInfo gloSvList[LOC_NUM_OF_GLO_FREQ_CHANNELS];
    /** Bit mask indicating which SVs have ephemeris data **/
    uint32_t      ephemerisMask;
    /** Bit mask indicating which GLONASS SVs have ephemeris data **/
    uint32_t      gloEphemerisMask;
    /** Bit mask indicating which SVs were used in latest sent fix **/
    uint32_t      svUsedInFixMask;
    /** Bit mask indicating which GLONASS SVs were used in latest sent fix **/
    uint32_t      gloSvUsedInFixMask;
    /** Bit mask indicating which QZSS SVs were used in latest sent fix **/
    uint32_t      qzssSvUsedInFixMask;
    /** Bit mask indicating which SBAS SVs were used in latest sent fix **/
    uint32_t      sbasSvUsedInFixMask;
} tLocSvStatus;


/** Application register this out callback function and CsrLocation class will pass outputted information to application */
typedef void (*csr_app_output_callback)(uint32_t msgId, void *const pMsgData, uint32_t msgLength);

/** Application register this event callback function and CsrLocation class will pass internal processing event to application */
typedef void (*csr_app_event_callback)(eCsrLocEventType event, uint32_t data);

/* General OSP message format */
typedef struct OspMsg {
    uint32_t msgId;
    uint32_t length;
    uint8_t  payload[4];
} tOspMsg;


/** CSRLocation class.
 *  A location interface to control location chip and get position and satellite information.
 */
class CSRLocation : public GPSProviderImplBase
{
public:
    /** Constructor: CsrLocation
     * Create the CSRLocation, accept specified configuration
     *
     * @param [in] pSerialLoc
     *             serial communication channel between host and GPS controller.
     * @param [in] pPinOnoff
     *             GPIO pin to control location chip on, a rising edge is used to activate
     *             location chip. Please note, before activate chip, reset pin should be
     *             pull high.
     * @param [in] pPinReset
     *             GPIO pin to control location chip reset, low level will keep location
     *             chip in hibernation state and high level will permit location chip to be
     *             activated.
     * @param [in] pWakeup
     *             GPIO pin to detect if the chip is still wakeup.
     * @param [in] pLocConfig
     *             Configuration including debug serial port, location communication serial port, onoff pin, reset pin
     * @param [in] debugP
     *             The debug port for diagnostic messages; can be NULL.
     */
    CSRLocation(RawSerial  &serialLoc,
                DigitalOut &pinOnoff,
                DigitalOut &pinReset,
                DigitalIn  &wakeup,
                Serial     *debugP = NULL);

    /** Destructor: CSRLocation
     * Free allocated resource
     */
    virtual ~CSRLocation();

    /** Register output callback and event callback functions
     * @param app_output_cb CSRLocation class output the location and satellite information to application
     * @param app_event_cb CSRLocation class output the start and stop result to application
     */
    void CsrLocRegOutput(csr_app_output_callback app_output_cb, csr_app_event_callback app_event_cb);

    /** HW reset to get location chip into hibernation mode */
    virtual void reset(void);

    /* A debug interface to switch location chip protocol from OSP at 115200bps to NMEA at 4800bps */
    void CsrLocDebugSwitch2Nmea(void);

private:
    /* Initialize the serial port and open it */
    void _CsrLocUartInit(void);

    /* Process the raw stream from location serial port */
    void _CsrLocProcessRawStream(void);

    /* Detect the OSP protocol detection timeout */
    void _CsrLocDetProtoOspTimeout(void);

    /* Detect the NMEA protocol outputted from location serial port */
    void _CsrLocDetProtoNmeaTimeout(void);

    /* Process the raw NMEA stream, remove the NMEA header, tail, and save the NMEA data into internal buffer */
    void _CsrLocProcessRawNmeaStream(uint8_t data);

    /* Process the raw OSP stream, remove the OSP header, size, check sum, and save the OSP data into internal buffer */
    void _CsrLocProcessRawOspStream(uint8_t data);

    /* Process the saved NMEA data and decode them */
    void _CsrLocProcessRawNmeaPkt(void);

    /* Process the saved OSP data and decode them */
    void _CsrLocProcessRawOspPkt(void);

    /* Calculate the OSP message size to allocate buffer to save the decoded OSP data */
    uint32_t _CsrLocCalcMsgSize(void);

    /* Decode OSP data into packet data structure */
    CsrResult _CsrLocDecodeOspPkt(uint8_t  *payload,
                                  uint32_t  payload_length,
                                  uint32_t *message_id,
                                  void     *message_structure,
                                  uint32_t *message_length);

    /* Process the decode OSP packet and pass to application when needed */
    void _CsrLocProcessOspPkt(tOspMsg *pOspMsg);

    /* Timeout process, such as detect OSP and NMEA protocol */
    void _CsrLocTimeout(void);

    /* Location serial port data receiver */
    void _CsrLocRxHandler(void);

    /* Send special OSP messages to location chip */
    void _CsrLocSendData(eSendDataType type);

    /* Trigger a pulse on the onoff pin */
    void _CsrLocHwOnoff(void);

    /* Trigger a reset on the reset pin */
    void _CsrLocHwReset(void);

    /* Detect wakeup status on the wakeup pin */
    bool _CsrLocIsWakeup(void);

private:
    void outputHandler(uint32_t msgId, void *const pMsgData, uint32_t msgLength);
    void eventHandler(eCsrLocEventType event, uint32_t data);

    /**
     * APIs needed to extend GPSProviderImplBase
     */
private:
    virtual bool setPowerMode(GPSProvider::PowerMode_t pwrMode);
    virtual void start(void);
    virtual void stop(void);
    virtual void process(void);
    virtual uint32_t ioctl(uint32_t command, void *arg);

    /** Special for low power PTF mode.
      * During low power PTF mode, after reporting position, chip will go to hibernation mode automatically.
      * After 30 seconds, chip will recover and report position again. Then chip will go to hibernation mode again.
      * During the hibernation, application can call lpmGetImmediateLocation to get position immediately and no need to wait for the whole interval.
      */
    virtual void lpmGetImmediateLocation(void);

    /* Internal data */
private:
    RawSerial       &serialLoc; /**< serial communication channel between host and GPS controller. */
    DigitalOut      &pinOnoff;
    DigitalOut      &pinReset;
    DigitalIn       &wakeup;

    bool             bPwrModeRsp;
    bool             bVerRsp;

    eProto           proto;
    eCsrLocState     locState;
    eProtoState      protoState;
    ePowerMode       pwrMode;

    uint32_t         baudRate;
    int32_t          computedCheckSum;
    int32_t          checksum;
    int32_t          msgSize;
    int32_t          decodeIndex;
    eProtoDetState   protoDetState;
    Timeout         *pTimeoutChk; /* timeout process */
    bool             bTimeoutFlag;
    eEngineStatus    engStatus;

    tLocSvStatus     svStatus; /* 2 kind of messages contribute the svStaus */

    uint8_t          serialBuf[MAX_SERIAL_BUF_LEN]; /* buffer the serial data from UART callback function */
    uint8_t          serialPkt[MAX_SERIAL_PKT_LEN]; /* decoded OSP data */
    uint32_t         in;
    uint32_t         out;

    csr_app_output_callback appOutCb;
    csr_app_event_callback  appEventCb;

    Serial *pSerialDebug;
};

#endif /* CSRLOCATION_H */