Q
Dependencies: SRF05 ros_lib_kinetic TinyGPSPlus
Diff: PROJ515.hpp
- Revision:
- 11:955c2ed70de2
- Parent:
- 10:7d954fba5e7a
- Child:
- 12:1a3272d67500
--- a/PROJ515.hpp Wed May 08 13:55:17 2019 +0000 +++ b/PROJ515.hpp Wed May 08 14:50:32 2019 +0000 @@ -15,31 +15,33 @@ #include "nav_msgs/Odometry.h" // ROS Odom Messages component #include "geometry_msgs/Twist.h" // ROS Twist 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_CF1T PA_4 // Cliff ultrasound 1 Trigger +#define USP_CF1E PA_3 // Cliff ultrasound 1 Echo +#define USP_CF2T PB_0 // Cliff ultrasound 2 Trigger +#define USP_CF2E PA_10 // Cliff ultrasound 2 Echo +#define USP_CF3T PC_1 // Cliff ultrasound 3 Trigger +#define USP_CF3E PB_3 // Cliff ultrasound 3 Echo +#define USP_CF4T PC_0 // Cliff ultrasound 4 Trigger +#define USP_CF4E PB_5 // 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 USP_CB1T PC_15 // Curb ultrasound 1 Trigger +#define USP_CB1E PB_4 // Curb ultrasound 1 Echo +#define USP_CB2T PC_14 // Curb ultrasound 2 Trigger +#define USP_CB2E PB_10 // Curb ultrasound 2 Echo +#define USP_CB3T PC_13 // Curb ultrasound 3 Trigger +#define USP_CB3E PA_8 // Curb ultrasound 3 Echo +#define USP_CB4T PB_7 // Curb ultrasound 4 Trigger +#define USP_CB4E PA_9 // Curb ultrasound 4 Echo -#define GPS_TX PD_5 // GPS Transmit Pin -#define GPS_RX PD_6 // GPS Recieve Pin +#define GPS_TX PC_10 // GPS Transmit Pin +#define GPS_RX PC_11 // GPS Recieve Pin + +#define LED_F PB_6 // LED Strip Front Data +#define LED_B PC_7 // LED Strip Back Data #define FOV 1.396 // Ultrasound sensor field of view #define MIN_RANGE 0.2 // Ultrasound sensor min range @@ -62,7 +64,6 @@ #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 @@ -72,6 +73,7 @@ using namespace ros; // Make all ros symbols visible using namespace sensor_msgs; // Make all sensor_msgs symbols visible using namespace std_msgs; // Make all std_msgs symbols visible +using namespace nav_msgs; using namespace Pololu; /* Declarations */ @@ -115,8 +117,8 @@ 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 +PololuLedStrip ledStripFront(LED_F);// LED Strip Front +PololuLedStrip ledStripBack(LED_B); // LED Strip Back rgb_color colors[LED_COUNT]; // RGB Colour Array // Instance for ROS node and messages @@ -145,10 +147,6 @@ 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; @@ -162,6 +160,9 @@ void setRosDist(); // Put distance in ROS messages void setRosStamp(); // Put time into ROS messages void publishRosMsg(); // Publish ROS messages +//void AudioStatusCB(const std_msgs::String &status); +//void VelocityCB(const nav_msgs::Odometry &odom); +float Map(float x, float in_min, float in_max, float out_min, float out_max); /*============================================================================*/ #endif // End of inclusion \ No newline at end of file