Integration of HCSR04 with Nucleo board. ROS Enabled

Dependencies:   mbed HCSR04

Revision:
2:2bdc0f9b1a69
Parent:
1:ca82df4237eb
--- a/main.cpp	Fri Sep 10 09:24:48 2021 +0000
+++ b/main.cpp	Mon Sep 27 09:36:02 2021 +0000
@@ -1,31 +1,29 @@
 #include "mbed.h"
 #include <ros.h>
-#include <std_msgs/Float32.h>
 #include <std_msgs/String.h>
-#include "SHARPIR.h"
-
+#include "hcsr04.h"
 
 ros::NodeHandle  nh;
 
-std_msgs::Float32 data;
-ros::Publisher sharpir("sharpir", &data);
+std_msgs::String data;
+ros::Publisher ultrasonic("ultrasonic", &data);
 
-SHARPIR Sensor(A0); 
-
+//D12 TRIGGER D11 ECHO
+HCSR04 sensor(D8, D9); 
 
 int main() {
-    float DistanceCM;
+    char buffer[50];
     
     nh.initNode();
-    nh.advertise(sharpir);
+    nh.advertise(ultrasonic);
     
     while (1) { //creates an eternal loop
-    
-        DistanceCM=Sensor.cm();  
-        //sprintf (buffer, "%f", DistanceCM);
         
-        data.data = DistanceCM;
-        sharpir.publish( &data );
+        long distance = sensor.distance();  
+        sprintf (buffer, "%d", distance);
+        
+        data.data = buffer;
+        ultrasonic.publish( &data );
         
         nh.spinOnce();
         wait_ms(1000);