Q

Dependencies:   SRF05 ros_lib_kinetic TinyGPSPlus

PROJ515.hpp

Committer:
Luka_Danilovic
Date:
2019-05-14
Revision:
15:d23cd07d24c0
Parent:
13:78b9acd2e873

File content as of revision 15:d23cd07d24c0:

#ifndef __PROJ515_H__ //Inclusion safeguards
#define __PROJ515_H__ //Definition of the inclusion
/*============================================================================*/

/* 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
#define LEDS_ON  0x07               // LED bus all on

#define USP_CF1T  PF_7              // Cliff ultrasound 1 Trigger
#define USP_CF1E  PE_15             // Cliff ultrasound 1 Echo
#define USP_CF2T  PF_8              // Cliff ultrasound 2 Trigger
#define USP_CF2E  PE_12             // Cliff ultrasound 2 Echo
#define USP_CF3T  PF_9              // Cliff ultrasound 3 Trigger
#define USP_CF3E  PB_10             // Cliff ultrasound 3 Echo
#define USP_CF4T  PG_1              // Cliff ultrasound 4 Trigger
#define USP_CF4E  PB_11             // Cliff ultrasound 4 Echo

#define USP_CB1T  PE_2              // Curb  ultrasound 1 Trigger
#define USP_CB1E  PG_14             // Curb  ultrasound 1 Echo
#define USP_CB2T  PE_4              // Curb  ultrasound 2 Trigger
#define USP_CB2E  PG_9              // Curb  ultrasound 2 Echo
#define USP_CB3T  PE_6              // Curb  ultrasound 3 Trigger
#define USP_CB3E  PE_7              // Curb  ultrasound 3 Echo
#define USP_CB4T  PE_5              // Curb  ultrasound 4 Trigger
#define USP_CB4E  PE_8              // Curb  ultrasound 4 Echo

#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.025             // Ultrasound sensor min range
#define MAX_RANGE 0.4               // Ultrasound sensor max range
#define CLIFF_TRH 0.12              // Robot cliff treshold
#define CLIFF_ZRO 0                 // Cliff not existent
#define EXCL_ZONE 0.15              // Robot footprint exclusion zone
#define ULTRASOUND 0x00             // Ultrasound

#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 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
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

/* Declarations */
extern float cfDist1;               // Distance returned by cliff u_sensor1 (m)
extern float cfDist2;               // Distance returned by cliff u_sensor2 (m)
extern float cfDist3;               // Distance returned by cliff u_sensor3 (m)
extern float cfDist4;               // Distance returned by cliff u_sensor4 (m)

extern float cbDist1;               // Distance returned by curb  u_sensor1 (m)
extern float cbDist2;               // Distance returned by curb  u_sensor2 (m)
extern float cbDist3;               // Distance returned by curb  u_sensor3 (m)
extern float cbDist4;               // Distance returned by curb  u_sensor4 (m)

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

/* Instantiations */
// Instance for ultrasound sensors
SRF05 USS_CF1(USP_CF1T, USP_CF1E);  // Ultrasound sensor cliff 1
SRF05 USS_CF2(USP_CF2T, USP_CF2E);  // Ultrasound sensor cliff 2
SRF05 USS_CF3(USP_CF3T, USP_CF3E);  // Ultrasound sensor cliff 3
SRF05 USS_CF4(USP_CF4T, USP_CF4E);  // Ultrasound sensor cliff 4

SRF05 USS_CB1(USP_CB1T, USP_CB1E);  // Ultrasound sensor cliff 1
SRF05 USS_CB2(USP_CB2T, USP_CB2E);  // Ultrasound sensor cliff 2
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 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

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); 
Publisher ultrasound_pub_cf4("ultrasound/cf4", &ultrasound_msg_cf4); 
Publisher ultrasound_pub_cb1("ultrasound/cb1", &ultrasound_msg_cb1); 
Publisher ultrasound_pub_cb2("ultrasound/cb2", &ultrasound_msg_cb2); 
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;

/* Function Prototypes */
void startSensors();                // Start the Sensors
void recordDist();                  // Record the Distances (meters)
void checkCliff();                  // Check the Cliff Sensors Readings
void advRosPub();                   // Adverstise Ultrasound Topic
void setupRosMsg();                 // Setup the message constant values
void setRosDist();                  // Put distance in ROS messages
void setRosStamp();                 // Put time into ROS messages
void publishRosMsg();               // Publish ROS messages

/*============================================================================*/
#endif // End of inclusion