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

Dependencies:   mbed VEML7700

Files at this revision

API Documentation at this revision

Comitter:
zillkhan
Date:
Tue Sep 28 12:39:31 2021 +0000
Parent:
1:ca82df4237eb
Commit message:
final code

Changed in this revision

SHARPIR.lib Show diff for this revision Revisions of this file
VEML7700.lib Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/SHARPIR.lib	Fri Sep 10 09:24:48 2021 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,1 +0,0 @@
-https://os.mbed.com/users/zillkhan/code/SHARPIR_GP2Y0A51SK0F/#acdd61a2aac7
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/VEML7700.lib	Tue Sep 28 12:39:31 2021 +0000
@@ -0,0 +1,1 @@
+https://developer.mbed.org/teams/MSS/code/VEML7700/#67634e08150f
--- 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);