Integration of Ambient Light sensor VEML7700 with Nucleo board. ROS Enabled

Dependencies:   mbed VEML7700

Revision:
2:1d1f6cd9d8b1
Parent:
1:ca82df4237eb
--- a/main.cpp	Fri Sep 10 09:24:48 2021 +0000
+++ b/main.cpp	Tue Sep 28 12:39:31 2021 +0000
@@ -1,31 +1,38 @@
 #include "mbed.h"
 #include <ros.h>
-#include <std_msgs/Float32.h>
-#include <std_msgs/String.h>
-#include "SHARPIR.h"
+#include <std_msgs/Int16.h>
+#include "VEML7700.h"
 
+#ifndef MSU_VEML7700_I2C_ADDRESS
+#define MSU_VEML7700_I2C_ADDRESS 0x10
+#endif
+
+#define PIN_SCL  D15
+#define PIN_SDA  D14
 
 ros::NodeHandle  nh;
 
-std_msgs::Float32 data;
-ros::Publisher sharpir("sharpir", &data);
+std_msgs::Int16 data;
+ros::Publisher ALS("ALS", &data);
 
-SHARPIR Sensor(A0); 
-
+VEML7700 *veml7700 = 0 ;
 
 int main() {
-    float DistanceCM;
+    uint16_t als ;
+    
+    veml7700 = new VEML7700(PIN_SDA, PIN_SCL, MSU_VEML7700_I2C_ADDRESS) ; 
+    veml7700->setALSConf(0x0000) ;
+    veml7700->setPowerSaving(0x0000) ;
     
     nh.initNode();
-    nh.advertise(sharpir);
+    nh.advertise(ALS);
     
     while (1) { //creates an eternal loop
     
-        DistanceCM=Sensor.cm();  
-        //sprintf (buffer, "%f", DistanceCM);
+        als = veml7700->getALS();
         
-        data.data = DistanceCM;
-        sharpir.publish( &data );
+        data.data = als;
+        ALS.publish( &data );
         
         nh.spinOnce();
         wait_ms(1000);