Luka Danilovic
/
PROJ515_GPS
GPS NMEA through NavSatFix
Diff: PROJ515.hpp
- Revision:
- 13:755a3cd9d35d
- Parent:
- 11:8e44351d580d
- Child:
- 14:90590736e700
diff -r b6e882262f93 -r 755a3cd9d35d PROJ515.hpp --- a/PROJ515.hpp Fri Mar 08 12:45:01 2019 +0000 +++ b/PROJ515.hpp Tue Mar 19 12:32:22 2019 +0000 @@ -6,7 +6,7 @@ #include "mbed.h" // Mbed RTOS #include "TinyGPSPlus.h" // GPS Module Library #include "ros.h" // ROS Library -#include "nav_msgs/Odometry.h" // ROS Navigation Messages component +#include "sensor_msgs/NavSatFix.h" // ROS Sensor Messages component #include "std_msgs/String.h" // ROS Standard Messages component //#include "std_msgs/Char.h" // ROS Standard Messages component @@ -16,16 +16,16 @@ #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 // ROS Baud Rate -#define ROS_Baud 921600 // ROS Baud Rate -#define frameID "gps_odom" // ROS frame ID -#define childID "base_link" // ROS child frame ID +#define ROS_Baud 921600 // ROS Baud Rate +#define frameID "gps_odom" // ROS frame ID #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 CVR 0x01 // Covariance value for rotational components +#define CVO 0x00 // Covariance value for zero components #define PRINT_DATA 0x01 // Thread communication event to print data /* Declarations */