Q
Dependencies: SRF05 ros_lib_kinetic TinyGPSPlus
PROJ515.hpp
- Committer:
- Luka_Danilovic
- Date:
- 2019-05-07
- Revision:
- 8:49306a01c52a
- Parent:
- 6:40fc84f50432
- Child:
- 9:2d9a0c9e5456
File content as of revision 8:49306a01c52a:
#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 "ros.h" // ROS Library #include "sensor_msgs/Range.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 PG_1 // Cliff ultrasound 1 Trigger #define USP_CF1E PB_11 // Cliff ultrasound 1 Echo #define USP_CF2T PF_9 // Cliff ultrasound 2 Trigger #define USP_CF2E PB_10 // Cliff ultrasound 2 Echo #define USP_CF3T PF_7 // Cliff ultrasound 3 Trigger #define USP_CF3E PE_15 // Cliff ultrasound 3 Echo #define USP_CF4T PF_8 // Cliff ultrasound 4 Trigger #define USP_CF4E PE_12 // Cliff ultrasound 4 Echo #define USP_CB1T PE_6 // Curb ultrasound 1 Trigger #define USP_CB1E PE_7 // Curb ultrasound 1 Echo #define USP_CB2T PE_5 // Curb ultrasound 2 Trigger #define USP_CB2E PE_8 // Curb ultrasound 2 Echo #define USP_CB3T PE_4 // Curb ultrasound 3 Trigger #define USP_CB3E PG_9 // Curb ultrasound 3 Echo #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 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 ROS_Baud 460800 // ROS Baud Rate #define frameID "ultrasound_range" // ROS frame ID #define ULTRASOUND 0x00 // Ultrasound #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 /* 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 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 // Instance for ROS publishers (Range message for cliff and curb sensors) 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); /* 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