Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependents: A_TeseoLocationNEW A_TeseoLocation
Teseo.h
00001 /** 00002 ******************************************************************************* 00003 * @file Teseo.h 00004 * @author AST / Central Lab 00005 * @version V1.0.0 00006 * @date May-2017 00007 * @brief Teseo Location Class 00008 * 00009 ******************************************************************************* 00010 * @attention 00011 * 00012 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2> 00013 * 00014 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); 00015 * You may not use this file except in compliance with the License. 00016 * You may obtain a copy of the License at: 00017 * 00018 * http://www.st.com/software_license_agreement_liberty_v2 00019 * 00020 * Redistribution and use in source and binary forms, with or without modification, 00021 * are permitted provided that the following conditions are met: 00022 * 1. Redistributions of source code must retain the above copyright notice, 00023 * this list of conditions and the following disclaimer. 00024 * 2. Redistributions in binary form must reproduce the above copyright notice, 00025 * this list of conditions and the following disclaimer in the documentation 00026 * and/or other materials provided with the distribution. 00027 * 3. Neither the name of STMicroelectronics nor the names of its contributors 00028 * may be used to endorse or promote products derived from this software 00029 * without specific prior written permission. 00030 * 00031 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00032 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00033 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00034 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00035 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00036 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00037 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00038 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00039 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00040 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00041 * 00042 ******************************************************************************** 00043 */ 00044 00045 #ifndef __TESEO_H__ 00046 #define __TESEO_H__ 00047 00048 #include "mbed.h" 00049 #include "GPSProviderImplBase.h" 00050 00051 #include "TeseoConfig.h" 00052 #include "NMEAParser.h" 00053 00054 #define STD_UART_BAUD 9600// 9600 00055 #define FWU_UART_BAUD 115200 00056 #define TESEO_I2C_ADDRESS 0x3A 00057 #define POWERON_STABLE_SIGNAL_DELAY_MS 150 00058 00059 /** Indicates the outputted location information */ 00060 #define LOC_OUTPUT_LOCATION (1) 00061 #define LOC_OUTPUT_NMEA (2) 00062 #define LOC_OUTPUT_PSTM (3) 00063 00064 #if 1 00065 #define TESEO_LOG_INFO(...) 00066 #else 00067 #define TESEO_LOG_INFO(...) { \ 00068 if (_serialDebug != NULL) { \ 00069 (_serialDebug->printf(__VA_ARGS__)); \ 00070 } \ 00071 } 00072 #endif 00073 00074 /** 00075 * @brief Constant that indicates the maximum number of nmea messages to be processed. 00076 */ 00077 #define NMEA_MSGS_NUM 6 //Note: update this constant coherently to eMsg enum type 00078 00079 /** 00080 * @brief Constant that indicates the maximum number of proprietary nmea messages to be processed. 00081 */ 00082 #define PSTM_NMEA_MSGS_NUM 5 //Note: update this constant coherently to ePSTMsg enum type 00083 00084 /** 00085 * @brief Constant that indicates the maximum number of positions that can be stored. 00086 */ 00087 #define MAX_STOR_POS 64 00088 00089 /** 00090 * @brief Constant that indicates the lenght of the buffer that stores the GPS data read by the GPS expansion. 00091 */ 00092 00093 #define TESEO_RXBUF_LEN 256//90 00094 #define TESEO_RXQUEUE_LEN 8 00095 00096 /** 00097 * @brief Enumeration structure that containes the two success states of a process 00098 */ 00099 typedef enum { 00100 TESEO_STATUS_SUCCESS = 0, /**< Success status */ 00101 TESEO_STATUS_FAILURE = 1 /**< Failure status */ 00102 } eStatus; 00103 00104 /** Location event definitions */ 00105 typedef enum { 00106 /** Start result event */ 00107 TESEO_LOC_EVENT_START_RESULT, 00108 /** Stop result event */ 00109 TESEO_LOC_EVENT_STOP_RESULT, 00110 } eTeseoLocEventType; 00111 00112 /** Teseo Location state */ 00113 typedef enum { 00114 TESEO_LOC_STATE_IDLE, 00115 TESEO_LOC_STATE_RUN, 00116 TESEO_LOC_STATE_FEATURE, 00117 TESEO_LOC_STATE_DEBUG 00118 } eTeseoLocState; 00119 00120 /** 00121 * @brief Enumeration structure that containes the two states of a debug process 00122 */ 00123 typedef enum { 00124 DEBUG_OFF = 0, /**< In this case, nothing will be printed on the console (nmea strings, positions and so on) */ 00125 DEBUG_ON = 1 /**< In this case, nmea strings and just acquired positions will be printed on the console */ 00126 } eDebugState; 00127 00128 /** 00129 * @brief Data structure that contains the driver informations 00130 */ 00131 typedef struct TeseoData { 00132 eDebugState debug; /**< Debug status */ 00133 GPGGA_Infos gpgga_data; /**< $GPGGA Data holder */ 00134 GNS_Infos gns_data; /**< $--GNS Data holder */ 00135 GPGST_Infos gpgst_data; /**< $GPGST Data holder */ 00136 GPRMC_Infos gprmc_data; /**< $GPRMC Data holder */ 00137 GSA_Infos gsa_data; /**< $--GSA Data holder */ 00138 GSV_Infos gsv_data; /**< $--GSV Data holder */ 00139 00140 Geofence_Infos geofence_data; /**< Geofence Data holder */ 00141 Odometer_Infos odo_data; /**< Odometer Data holder */ 00142 Datalog_Infos datalog_data; /**< Datalog Data holder */ 00143 00144 Ack_Info ack; /**< */ 00145 00146 } tTeseoData; 00147 00148 /** Application register this out callback function and Teseo class will pass outputted information to application */ 00149 typedef void (*teseo_app_output_callback)(uint32_t msgId, uint32_t msgType, tTeseoData *pData); 00150 /** Application register this event callback function and Teseo class will pass internal processing event to application */ 00151 typedef void (*teseo_app_event_callback)(eTeseoLocEventType event, uint32_t data); 00152 00153 class Teseo : public GPSProviderImplBase { 00154 public: 00155 00156 typedef enum { 00157 TEST, 00158 GETSWVER, 00159 FORCESTANDBY, 00160 RFTESTON, 00161 RFTESTOFF, 00162 LOWPOWER, 00163 FWUPDATE 00164 } eCmd; 00165 00166 /** NMEA messages types */ 00167 typedef enum { 00168 GPGGA, 00169 GNS, 00170 GPGST, 00171 GPRMC, 00172 GSA, 00173 GSV, 00174 } eMsg; 00175 00176 /** NMEA proprietary messages types */ 00177 typedef enum { 00178 PSTMGEOFENCE, 00179 PSTMODO, 00180 PSTMDATALOG, 00181 PSTMSGL, 00182 PSTMSAVEPAR 00183 } ePSTMsg; 00184 00185 private: 00186 00187 eTeseoLocState _locState; 00188 00189 DigitalOut _loc_led2; 00190 DigitalOut _reset; 00191 DigitalOut _pps; 00192 DigitalOut _wakeup; 00193 PinName _uartRx; 00194 PinName _uartTx; 00195 00196 Serial *_uart; 00197 Serial *_serialDebug; 00198 I2C *_i2c; 00199 00200 tTeseoData pData; 00201 GPGGA_Infos stored_positions[MAX_STOR_POS]; 00202 00203 int FwWaitAck(); 00204 00205 Thread *serialStreamThread; 00206 00207 /** 00208 * Command string 00209 */ 00210 char _teseoCmd[TESEO_RXBUF_LEN]; 00211 00212 /** 00213 * Message struct 00214 */ 00215 struct _teseoMsg { 00216 uint8_t len; 00217 uint8_t buf[TESEO_RXBUF_LEN]; 00218 }; 00219 00220 public: 00221 00222 /** Constructor: Teseo 00223 * Create the Teseo, accept specified configuration 00224 * 00225 * @param [in] resetPin 00226 * GPIO pin to control location chip reset. 00227 * @param [in] wakeupPin 00228 * GPIO pin to detect if the chip is still wakeup. 00229 * @param [in] ppsPin 00230 * GPIO pin... . 00231 * @param [in] uartTxPin 00232 * GPIO pin for serial Tx channel between the host and the GNSS controller. 00233 * @param [in] uartRxPin 00234 * GPIO pin for serial Rx channel between the host and the GNSS controller. 00235 * @param [in] serialDebug 00236 * The debug port for diagnostic messages; can be NULL. 00237 */ 00238 Teseo(PinName resetPin, 00239 PinName wakeupPin, 00240 PinName ppsPin, 00241 PinName uartTxPin, 00242 PinName uartRxPin, 00243 Serial *serialDebug = NULL); 00244 00245 /** Constructor: Teseo 00246 * Create the Teseo, accept specified configuration 00247 * 00248 * @param [in] resetPin 00249 * GPIO pin to control location chip reset. 00250 * @param [in] wakeupPin 00251 * GPIO pin to detect if the chip is still wakeup. 00252 * @param [in] ppsPin 00253 * GPIO pin... . 00254 * @param [in] uartTxPin 00255 * GPIO pin for serial Tx channel between the host and the GNSS controller. 00256 * @param [in] uartRxPin 00257 * GPIO pin for serial Rx channel between the host and the GNSS controller. 00258 * @param [in] i2cBus 00259 * I2C Bus not supported yet. 00260 * @param [in] serialDebug 00261 * The debug port for diagnostic messages; can be NULL. 00262 */ 00263 Teseo(PinName resetPin, 00264 PinName wakeupPin, 00265 PinName ppsPin, 00266 PinName uartTxPin, 00267 PinName uartRxPin, 00268 I2C *i2cBus, 00269 Serial *serialDebug = NULL); 00270 00271 /** Register output callback and event callback functions 00272 * @param app_output_cb Teseo class output the location and satellite information to application 00273 * @param app_event_cb Teseo class output the start and stop result to application 00274 */ 00275 void TeseoLocRegOutput(teseo_app_output_callback app_output_cb, teseo_app_event_callback app_event_cb); 00276 00277 void SendCommand(Teseo::eCmd c); 00278 void SendCommand(char *cmd); 00279 00280 int EnableLowPower(); 00281 00282 void ReadSentence(Teseo::eMsg msg); 00283 00284 eStatus WakeStatus(void){ 00285 return _wakeup.read() ? TESEO_STATUS_SUCCESS : TESEO_STATUS_FAILURE; 00286 } 00287 00288 void ReadProcess(void); 00289 00290 private: 00291 00292 virtual bool setPowerMode(GPSProvider::PowerMode_t pwrMode); 00293 virtual void start(void); 00294 virtual void stop(void); 00295 virtual void process(void); 00296 virtual void reset(void); 00297 virtual const GPSProvider::LocationUpdateParams_t *getLastLocation(void) const; 00298 00299 gps_provider_error_t cfgMessageList(int level); 00300 gps_provider_error_t saveConfigParams(void); 00301 00302 /** Set NMEA stream verbosity */ 00303 virtual void setVerboseMode(int level); 00304 00305 /** Geofencing */ 00306 virtual bool isGeofencingSupported(void); 00307 virtual gps_provider_error_t enableGeofence(void); 00308 virtual gps_provider_error_t configGeofences(GPSGeofence *geofences[], unsigned geofenceCount); 00309 virtual gps_provider_error_t geofenceReq(void); 00310 gps_provider_error_t cfgGeofenceCircle(void); 00311 00312 /** Datalogging */ 00313 virtual bool isDataloggingSupported(void); 00314 virtual gps_provider_error_t enableDatalog(void); 00315 virtual gps_provider_error_t configDatalog(GPSDatalog *datalog); 00316 virtual gps_provider_error_t startDatalog(void); 00317 virtual gps_provider_error_t stopDatalog(void); 00318 virtual gps_provider_error_t eraseDatalog(void); 00319 virtual gps_provider_error_t logReqStatus(void); 00320 virtual gps_provider_error_t logReqQuery(GPSProvider::LogQueryParams_t &logReqQuery); 00321 00322 /* Odometer */ 00323 virtual bool isOdometerSupported(void); 00324 virtual gps_provider_error_t enableOdo(void); 00325 virtual gps_provider_error_t startOdo(unsigned alarmDistance); 00326 virtual gps_provider_error_t stopOdo(void); 00327 virtual gps_provider_error_t resetOdo(void); 00328 00329 void _InitUART(int br = STD_UART_BAUD); 00330 void _ResetFast(Serial *serialDebug = NULL); 00331 void _Reset(Serial *serialDebug = NULL); 00332 void _SendString(char *buf, int len); 00333 int _WakeUp(); 00334 int _CRC(char *buf, int size); 00335 00336 /** 00337 * @brief This function gets a chunck of NMEA messages 00338 * @param msg NMEA message to search for 00339 * @retval eStatus TESEO_STATUS_SUCCESS if the parse process goes ok, TESEO_FAILURE if it doesn't 00340 */ 00341 eStatus _GetMsg(Teseo::eMsg msg, uint8_t *buffer); 00342 /** 00343 * @brief This function gets a chunck of PSTM NMEA messages 00344 * @param msg PSTM NMEA message to search for 00345 * @retval eStatus TESEO_STATUS_SUCCESS if the parse process goes ok, TESEO_FAILURE if it doesn't 00346 */ 00347 void _GetPSTMsg(Teseo::ePSTMsg msg, uint8_t *buffer); 00348 void _GetLocationMsg(Teseo::eMsg msg, uint8_t *buffer); 00349 00350 void _LocLed2Set(void){ 00351 _loc_led2.write(1); 00352 } 00353 void _LocLed2Reset(void){ 00354 _loc_led2.write(0); 00355 } 00356 00357 void outputHandler(uint32_t msgId, uint32_t msgType, tTeseoData *pData); 00358 void eventHandler(eTeseoLocEventType event, uint32_t data); 00359 00360 teseo_app_output_callback appOutCb; 00361 teseo_app_event_callback appEventCb; 00362 00363 MemoryPool<struct _teseoMsg, TESEO_RXQUEUE_LEN> mpool; 00364 Queue<struct _teseoMsg, TESEO_RXQUEUE_LEN> queue; 00365 }; 00366 00367 #endif /*__TESEO_H__*/
Generated on Wed Jul 13 2022 01:04:53 by
