Q

Dependencies:   SRF05 ros_lib_kinetic TinyGPSPlus

Revision:
10:7d954fba5e7a
Parent:
9:2d9a0c9e5456
Child:
11:955c2ed70de2
--- a/PROJ515.hpp	Wed May 08 10:29:11 2019 +0000
+++ b/PROJ515.hpp	Wed May 08 13:55:17 2019 +0000
@@ -6,9 +6,14 @@
 #include "mbed.h"                   // Mbed RTOS
 #include "SRF05.h"                  // SRF05 ultrasound sensor custom libary
 #include "TinyGPSPlus.h"            // GPS Module Library
+#include "PololuLedStrip.h"         // LED Strip Library
+#include "string"                   // Character String Library
 #include "ros.h"                    // ROS Library
+#include "std_msgs/String.h"        // ROS String Messages component
 #include "sensor_msgs/Range.h"      // ROS Sensor Messages component
 #include "sensor_msgs/NavSatFix.h"  // ROS Sensor Messages component
+#include "nav_msgs/Odometry.h"      // ROS Odom   Messages component
+#include "geometry_msgs/Twist.h"    // ROS Twist  Messages component
 
 
 /* Definitions */
@@ -52,6 +57,9 @@
 #define CVZ 0x01                    // Covariance value for X from the datasheet
 #define CVO 0x00                    // Covariance value for zero components
 
+#define LED_COUNT 30                // LED strip LED count
+#define MaxVelocity 0.5             // Max Wheel Velocity
+
 #define ROS_Baud  460800            // ROS Baud Rate
 #define GPS_Baud  9600              // GPS Baud Rate
 //#define frameID_u "ultrasound_range"// ROS frame ID
@@ -63,7 +71,8 @@
 using namespace std;                // Make all std symbols visible
 using namespace ros;                // Make all ros symbols visible
 using namespace sensor_msgs;        // Make all sensor_msgs symbols visible
-using namespace std_msgs;           // Make all sdt_msgs symbols visible
+using namespace std_msgs;           // Make all std_msgs symbols visible
+using namespace Pololu;
 
 /* Declarations */
 extern float cfDist1;               // Distance returned by cliff u_sensor1 (m)
@@ -78,8 +87,12 @@
 
 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    
+extern char  gps_c;                 // GPS stream character - Defined in PROJ515.cpp
+extern int   sats_n;                // GPS satelite number  - Defined in PROJ515.cpp  
+
+extern float vel;                   // Odom linear  velocity 
+extern float ang;                   // Odom angular velocity
+extern string audio_state;          // Audio Information (Playing/Stopped)
 
 /* GPIO */
 DigitalIn bttn(USER_BUTTON);        // Onboard blue user button
@@ -98,8 +111,13 @@
 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
+TinyGPSPlus gpsModule;              // Instance of GPS class
+Serial gpsSer(GPS_TX, GPS_RX);      // Instance of Serial class to gps
+
+// Instance for LED Strip
+PololuLedStrip ledStripFront();   // LED Strip Front
+PololuLedStrip ledStripBack();    // LED Strip Back
+rgb_color colors[LED_COUNT];        // RGB Colour Array
 
 // Instance for ROS node and messages
 NodeHandle nh;                      // Instance for ROS Node Handler
@@ -127,6 +145,10 @@
 
 Publisher gps_odom_pub("gps_odom", &gps_odom_msg);
 
+// Instance for ROS subscribers
+ros::Subscriber<std_msgs::String> AudioStatus("audio_status", &AudioStatusCB);
+ros::Subscriber<nav_msgs::Odometry> Velocity("wheel_odom/exact_odom", &VelocityCB);
+
 /* Threads and Signals */
 //Thread myThread (osPriorityNormal);
 //EventFlags myEventFlag;