Q

Dependencies:   SRF05 ros_lib_kinetic TinyGPSPlus

Revision:
9:2d9a0c9e5456
Parent:
8:49306a01c52a
Child:
10:7d954fba5e7a
--- a/PROJ515.hpp	Tue May 07 15:57:01 2019 +0000
+++ b/PROJ515.hpp	Wed May 08 10:29:11 2019 +0000
@@ -5,8 +5,11 @@
 /* Libraries */
 #include "mbed.h"                   // Mbed RTOS
 #include "SRF05.h"                  // SRF05 ultrasound sensor custom libary
+#include "TinyGPSPlus.h"            // GPS Module Library
 #include "ros.h"                    // ROS Library
 #include "sensor_msgs/Range.h"      // ROS Sensor Messages component
+#include "sensor_msgs/NavSatFix.h"  // ROS Sensor Messages component
+
 
 /* Definitions */
 #define LEDS_OFF 0x00               // LED bus all off
@@ -30,18 +33,31 @@
 #define USP_CB4T  PE_2              // Curb  ultrasound 4 Trigger
 #define USP_CB4E  PG_14             // Curb  ultrasound 4 Echo
 
-#define FOV 1.396                   // Ultrasound sensor field of view
+#define GPS_TX    PD_5              // GPS Transmit Pin
+#define GPS_RX    PD_6              // GPS Recieve  Pin
+
+#define FOV       1.396             // Ultrasound sensor field of view
 #define MIN_RANGE 0.2               // Ultrasound sensor min range
 #define MAX_RANGE 2.5               // Ultrasound sensor max range
 #define CLIFF_TRH 0.1               // Robot cliff treshold
 #define CLIFF_ZRO 0                 // Cliff not existent
 #define EXCL_ZONE 0.255             // Robot footprint exclusion zone
+#define ULTRASOUND 0x00             // Ultrasound
 
-#define ROS_Baud 460800             // ROS Baud Rate
-#define frameID "ultrasound_range"  // ROS frame ID
+#define UNAGUMENTED  0x00           // Unagumented 
+#define GPS_CONSTELL 0x01           // GPS constellation
+#define UNNWN        0x00           // Unknown 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 CVO 0x00                    // Covariance value for zero components
 
-#define ULTRASOUND 0x00             // Ultrasound
-#define PRINT_DATA 0x01             // Thread communication event to print data 
+#define ROS_Baud  460800            // ROS Baud Rate
+#define GPS_Baud  9600              // GPS Baud Rate
+//#define frameID_u "ultrasound_range"// ROS frame ID
+#define frameID_g "gps_odom"        // ROS frame ID
+
+//#define PRINT_DATA 0x01             // Thread communication event to print data 
 
 /* Namespaces */
 using namespace std;                // Make all std symbols visible
@@ -62,6 +78,9 @@
 
 extern float wPeriod;               // Wait period(ms) for ROS publisher
 
+extern char gps_c;                  // GPS stream character - Defined in PROJ515.cpp
+extern int  sats_n;                 // GPS satelite number  - Defined in PROJ515.cpp    
+
 /* GPIO */
 DigitalIn bttn(USER_BUTTON);        // Onboard blue user button
 BusOut leds(LED1, LED2, LED3);      // Onboard LEDs bus
@@ -78,19 +97,25 @@
 SRF05 USS_CB3(USP_CB3T, USP_CB3E);  // Ultrasound sensor cliff 3
 SRF05 USS_CB4(USP_CB4T, USP_CB4E);  // Ultrasound sensor cliff 4
 
+// Instance for GPS
+TinyGPSPlus gpsModule;                             // Instance of GPS class
+Serial gpsSer(GPS_TX, GPS_RX);                     // Instance of Serial class to gps
+
 // Instance for ROS node and messages
 NodeHandle nh;                      // Instance for ROS Node Handler
 
-Range ultrasound_msg_cf1;           // Instance for ROS NavSatFix message 1
-Range ultrasound_msg_cf2;           // Instance for ROS NavSatFix message 2
-Range ultrasound_msg_cf3;           // Instance for ROS NavSatFix message 3
-Range ultrasound_msg_cf4;           // Instance for ROS NavSatFix message 4
-Range ultrasound_msg_cb1;           // Instance for ROS NavSatFix message 5
-Range ultrasound_msg_cb2;           // Instance for ROS NavSatFix message 6
-Range ultrasound_msg_cb3;           // Instance for ROS NavSatFix message 7
-Range ultrasound_msg_cb4;           // Instance for ROS NavSatFix message 8
+Range ultrasound_msg_cf1;           // Instance for ROS Range message 1
+Range ultrasound_msg_cf2;           // Instance for ROS Range message 2
+Range ultrasound_msg_cf3;           // Instance for ROS Range message 3
+Range ultrasound_msg_cf4;           // Instance for ROS Range message 4
+Range ultrasound_msg_cb1;           // Instance for ROS Range message 5
+Range ultrasound_msg_cb2;           // Instance for ROS Range message 6
+Range ultrasound_msg_cb3;           // Instance for ROS Range message 7
+Range ultrasound_msg_cb4;           // Instance for ROS Range message 8
 
-// Instance for ROS publishers (Range message for cliff and curb sensors)
+NavSatFix gps_odom_msg;             // Instance for ROS NavSatFix message
+
+// Instance for ROS publishers
 Publisher ultrasound_pub_cf1("ultrasound/cf1", &ultrasound_msg_cf1); 
 Publisher ultrasound_pub_cf2("ultrasound/cf2", &ultrasound_msg_cf2); 
 Publisher ultrasound_pub_cf3("ultrasound/cf3", &ultrasound_msg_cf3); 
@@ -100,6 +125,8 @@
 Publisher ultrasound_pub_cb3("ultrasound/cb3", &ultrasound_msg_cb3); 
 Publisher ultrasound_pub_cb4("ultrasound/cb4", &ultrasound_msg_cb4); 
 
+Publisher gps_odom_pub("gps_odom", &gps_odom_msg);
+
 /* Threads and Signals */
 //Thread myThread (osPriorityNormal);
 //EventFlags myEventFlag;