Luka Danilovic
/
PROJ515_GPS
GPS NMEA through NavSatFix
Diff: PROJ515.hpp
- Revision:
- 3:30c3f20c2387
- Parent:
- 2:a2e5b48beaa1
- Child:
- 4:df54ebe69b38
--- a/PROJ515.hpp Tue Feb 26 14:28:47 2019 +0000 +++ b/PROJ515.hpp Fri Mar 01 11:48:05 2019 +0000 @@ -4,7 +4,7 @@ /* Libraries */ #include "mbed.h" // Mbed RTOS -#include <string> // Standard C++ String +//#include "USBSerial.h" // Serial over second USB #include "TinyGPSPlus.h" // GPS Module Library #include "ros.h" // ROS Library #include "nav_msgs/Odometry.h" // ROS Navigation Messages component @@ -12,25 +12,27 @@ #include "std_msgs/Char.h" // ROS Standard Messages component /* Definitions */ -#define GPS_TX PD_5 // GPS Transmit Pin -#define GPS_RX PD_6 // GPS Recieve Pin +#define GPS_TX PC_10 // GPS Transmit Pin +#define GPS_RX PC_11 // GPS Recieve Pin +#define USB_TX PC_12 // USB Transmit Pin +#define USB_RX PD_2 // USB Recieve Pin #define GPS_Baud 9600 // GPS Baud Rate -#define USB_Baud 9600 // USB Baud Rate -#define PRINT_DATA 0x01 // Signal to Thread to start Printing Data +#define USB_Baud 9600 // ROS Baud Rate +#define ROS_Baud 57600 // ROS Baud Rate #define frameID "/gps_odom" // ROS frame ID #define childID "/base_link" // ROS child frame ID -#define ZRO 0x00 // Hard coded 0 -#define ONE 0x01 // Hard coded 1 -#define CVL 0x1869F // Hard coded 99999 for covariance #define CVX 0x01 // Covariance value for X from the datasheet #define CVY 0x01 // Covariance value for X from the datasheet #define CVZ 0x01 // Covariance value for X from the datasheet +#define ONE 0x01 // Hard coded covariance of 1 +#define PRINT_DATA 0x01 /* Declarations */ extern char gps_c; // GPS stream character - Defined in PROJ515.cpp /* Function prototypes */ -void streamF(); +void streamF(); // Function prototype for streaming data +void setupRosMsg(); // Function prototype for seting up ROS messages /*============================================================================*/ #endif // End of inclusion \ No newline at end of file