Zill Khan / Mbed 2 deprecated ROSSerial_MultipleSensors

Dependencies:   mbed HCSR04 VEML7700

Files at this revision

API Documentation at this revision

Comitter:
zillkhan
Date:
Sat Oct 23 07:49:00 2021 +0000
Parent:
3:c23614e6262f
Commit message:
Adding BME680 driver

Changed in this revision

BME680.lib Show annotated file Show diff for this revision Revisions of this file
BME680_driver.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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/BME680.lib	Sat Oct 23 07:49:00 2021 +0000
@@ -0,0 +1,1 @@
+https://github.com/sensidev/BME680/#cd2aeb67003ce13c4e51a56a4fb935844289de53
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/BME680_driver.lib	Sat Oct 23 07:49:00 2021 +0000
@@ -0,0 +1,1 @@
+https://github.com/BoschSensortec/BME680_driver/#9014031fa00a5cc1eea1498c4cd1f94ec4b8ab11
--- a/main.cpp	Sat Oct 23 07:31:18 2021 +0000
+++ b/main.cpp	Sat Oct 23 07:49:00 2021 +0000
@@ -5,6 +5,7 @@
 #include "SHARPIR.h"
 #include "hcsr04.h"
 #include "VEML7700.h"
+#include "mbed_bme680.h"
 
 #ifndef MSU_VEML7700_I2C_ADDRESS
 #define MSU_VEML7700_I2C_ADDRESS 0x10
@@ -20,6 +21,10 @@
 //D8 TRIGGER D9 ECHO
 HCSR04 sensor(D8, D9);
 
+// BME680 pin defination
+I2C i2c(PIN_SDA, PIN_SCL);  
+BME680 bme680(0xEE); //I2C address for BME680
+
 ros::NodeHandle  nh;
 
 //SharpIR publisher initialization
@@ -34,11 +39,16 @@
 std_msgs::Int16 data_als;
 ros::Publisher ALS("ALS", &data_als);
 
+//BME680 publisher initialization
+std_msgs::String msg;
+ros::Publisher sensor_bme("sensor_bme", &msg);
+
 VEML7700 *veml7700 = 0 ;
 
 int main() {
     float DistanceCM; //Variable to store distance in CM from SharpIR sensor
     char buffer[50]; // buffer for Ultrasonic sensor values
+    char buff_bme[50]; // buffer for bme690 sensor values
     
     //Initialization of Ambient light sensor
     uint16_t als ;
@@ -46,20 +56,34 @@
     veml7700->setALSConf(0x0000) ;
     veml7700->setPowerSaving(0x0000) ;
     
+    //Initalization of BME680
+    if (!bme680.begin()) {
+        printf("BME680 Begin failed \r\n");
+        return 1;
+    }
+    
     //Initalizing and advertising topics
     nh.initNode();
     nh.advertise(sharpir); //SharpIR sensor
     nh.advertise(ultrasonic); //Ultrasonic Sensor
     nh.advertise(ALS); //Ambient Light Sensor
+    nh.advertise(sensor_bme); //bme680 sensor
     
     while (1) { //creates an eternal loop
     
         DistanceCM=Sensor.cm(); //Reading SharpIR sensor value from analog pin
+        wait_ms(500);
         
         long distance = sensor.distance(); //Reading ultrasonic sensor value
         sprintf (buffer, "%d", distance);  //converting value into string
+        wait_ms(500);
         
         als = veml7700->getALS(); //Readinng ALS sensor value
+        wait_ms(500);
+        
+        bme680.performReading(); //Reading bme680 value
+        sprintf (buff_bme, "Temp: %0.2f degC,Humi: %0.2f %%,Pres: %0.2f hPa,VOC: %0.2f KOhms", bme680.getTemperature(),bme680.getHumidity(),(bme680.getPressure() / 100.0),(bme680.getGasResistance() / 1000.0));
+        wait_ms(500);
         
         data_ir.data = DistanceCM;
         sharpir.publish( &data_ir );
@@ -70,6 +94,9 @@
         data_als.data = als;
         ALS.publish( &data_als );
         
+        msg.data = buffer;
+        sensor_bme.publish(&msg);
+        
         nh.spinOnce();
         wait_ms(1000);
     }