Integration of multiple sensors with ROS Serial

Dependencies:   mbed HCSR04 VEML7700

Revision:
2:b847309a754d
Parent:
1:3a7e10c8a325
Child:
3:c23614e6262f
--- a/main.cpp	Sat Oct 23 06:57:18 2021 +0000
+++ b/main.cpp	Sat Oct 23 07:17:03 2021 +0000
@@ -2,34 +2,47 @@
 #include <std_msgs/Float32.h>
 #include <std_msgs/String.h>
 #include "SHARPIR.h"
+#include "hcsr04.h"
 
 
 //Sharp IR sensor analog pin defination
 SHARPIR Sensor(A0); 
 
+//Ultrasonic sensor pin defination
+//D8 TRIGGER D9 ECHO
+HCSR04 sensor(D8, D9);
+
 ros::NodeHandle  nh;
 
 
 //SharpIR publisher initialization
-std_msgs::Float32 data;
-ros::Publisher sharpir("sharpir", &data);
+std_msgs::Float32 data_ir;
+ros::Publisher sharpir("sharpir", &data_ir);
 
-
+//Ultrasonic sensor publisher initialization
+std_msgs::String data_ul;
+ros::Publisher ultrasonic("ultrasonic", &data_ul);
 
 int main() {
     float DistanceCM; //Variable to store distance in CM from SharpIR sensor
+    char buffer[50]; // buffer for Ultrasonic sensor values
     
     //Initalizing and advertising topics
     nh.initNode();
-    nh.advertise(sharpir);
+    nh.advertise(sharpir); //SharpIR sensor
+    nh.advertise(ultrasonic); //Ultrasonic Sensor
     
     while (1) { //creates an eternal loop
     
-        DistanceCM=Sensor.cm();  
-
+        DistanceCM=Sensor.cm(); //Reading SharpIR sensor value from analog pin
+        long distance = sensor.distance(); //Reading ultrasonic sensor value
+        sprintf (buffer, "%d", distance);  //converting value into string
         
-        data.data = DistanceCM;
-        sharpir.publish( &data );
+        data_ir.data = DistanceCM;
+        sharpir.publish( &data_ir );
+        
+        data_ul.data = buffer;
+        ultrasonic.publish( &data_ul );
         
         nh.spinOnce();
         wait_ms(1000);