Integration of multiple sensors with ROS Serial

Dependencies:   mbed HCSR04 VEML7700

Revision:
0:d409714cebbf
Child:
1:3a7e10c8a325
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Sat Oct 23 06:48:13 2021 +0000
@@ -0,0 +1,32 @@
+#include <ros.h>
+#include <std_msgs/Float32.h>
+#include <std_msgs/String.h>
+#include "SHARPIR.h"
+
+
+ros::NodeHandle  nh;
+
+std_msgs::Float32 data;
+ros::Publisher sharpir("sharpir", &data);
+
+SHARPIR Sensor(A0); 
+
+
+int main() {
+    float DistanceCM;
+    
+    nh.initNode();
+    nh.advertise(sharpir);
+    
+    while (1) { //creates an eternal loop
+    
+        DistanceCM=Sensor.cm();  
+        //sprintf (buffer, "%f", DistanceCM);
+        
+        data.data = DistanceCM;
+        sharpir.publish( &data );
+        
+        nh.spinOnce();
+        wait_ms(1000);
+    }
+}