GPS NMEA through NavSatFix

Dependencies:   TinyGPSPlus

Committer:
Luka_Danilovic
Date:
Tue Feb 26 14:28:47 2019 +0000
Revision:
2:a2e5b48beaa1
Parent:
1:b610535e5879
Child:
3:30c3f20c2387
broken messages and location;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Luka_Danilovic 0:448e0e74e00f 1 #ifndef __PROJ515_H__ //Inclusion safeguards
Luka_Danilovic 0:448e0e74e00f 2 #define __PROJ515_H__ //Definition of the inclusion
Luka_Danilovic 0:448e0e74e00f 3 /*============================================================================*/
Luka_Danilovic 0:448e0e74e00f 4
Luka_Danilovic 0:448e0e74e00f 5 /* Libraries */
Luka_Danilovic 0:448e0e74e00f 6 #include "mbed.h" // Mbed RTOS
Luka_Danilovic 1:b610535e5879 7 #include <string> // Standard C++ String
Luka_Danilovic 0:448e0e74e00f 8 #include "TinyGPSPlus.h" // GPS Module Library
Luka_Danilovic 0:448e0e74e00f 9 #include "ros.h" // ROS Library
Luka_Danilovic 0:448e0e74e00f 10 #include "nav_msgs/Odometry.h" // ROS Navigation Messages component
Luka_Danilovic 0:448e0e74e00f 11 #include "std_msgs/String.h" // ROS Standard Messages component
Luka_Danilovic 2:a2e5b48beaa1 12 #include "std_msgs/Char.h" // ROS Standard Messages component
Luka_Danilovic 0:448e0e74e00f 13
Luka_Danilovic 0:448e0e74e00f 14 /* Definitions */
Luka_Danilovic 1:b610535e5879 15 #define GPS_TX PD_5 // GPS Transmit Pin
Luka_Danilovic 1:b610535e5879 16 #define GPS_RX PD_6 // GPS Recieve Pin
Luka_Danilovic 0:448e0e74e00f 17 #define GPS_Baud 9600 // GPS Baud Rate
Luka_Danilovic 0:448e0e74e00f 18 #define USB_Baud 9600 // USB Baud Rate
Luka_Danilovic 0:448e0e74e00f 19 #define PRINT_DATA 0x01 // Signal to Thread to start Printing Data
Luka_Danilovic 0:448e0e74e00f 20 #define frameID "/gps_odom" // ROS frame ID
Luka_Danilovic 0:448e0e74e00f 21 #define childID "/base_link" // ROS child frame ID
Luka_Danilovic 0:448e0e74e00f 22 #define ZRO 0x00 // Hard coded 0
Luka_Danilovic 0:448e0e74e00f 23 #define ONE 0x01 // Hard coded 1
Luka_Danilovic 0:448e0e74e00f 24 #define CVL 0x1869F // Hard coded 99999 for covariance
Luka_Danilovic 0:448e0e74e00f 25 #define CVX 0x01 // Covariance value for X from the datasheet
Luka_Danilovic 0:448e0e74e00f 26 #define CVY 0x01 // Covariance value for X from the datasheet
Luka_Danilovic 0:448e0e74e00f 27 #define CVZ 0x01 // Covariance value for X from the datasheet
Luka_Danilovic 0:448e0e74e00f 28
Luka_Danilovic 0:448e0e74e00f 29 /* Declarations */
Luka_Danilovic 1:b610535e5879 30 extern char gps_c; // GPS stream character - Defined in PROJ515.cpp
Luka_Danilovic 0:448e0e74e00f 31
Luka_Danilovic 0:448e0e74e00f 32 /* Function prototypes */
Luka_Danilovic 0:448e0e74e00f 33 void streamF();
Luka_Danilovic 0:448e0e74e00f 34
Luka_Danilovic 0:448e0e74e00f 35 /*============================================================================*/
Luka_Danilovic 0:448e0e74e00f 36 #endif // End of inclusion