![](/media/cache/img/default_profile.jpg.50x50_q85.jpg)
The integration of BME680 sensor with Nucleo board. ROS Enabled
Diff: main.cpp
- Revision:
- 2:816ad5bfa327
- Parent:
- 1:ca82df4237eb
--- a/main.cpp Fri Sep 10 09:24:48 2021 +0000 +++ b/main.cpp Tue Sep 28 12:41:58 2021 +0000 @@ -1,33 +1,43 @@ #include "mbed.h" #include <ros.h> -#include <std_msgs/Float32.h> -#include <std_msgs/String.h> -#include "SHARPIR.h" +#include "std_msgs/String.h" +#include "mbed_bme680.h" + +#define I2C_SDA D14 +#define I2C_SCL D15 + +I2C i2c(I2C_SDA, I2C_SCL); // Used inside the BME680 Mbed Lib. + +BME680 bme680(0xEE); -ros::NodeHandle nh; +ros::NodeHandle nh; -std_msgs::Float32 data; -ros::Publisher sharpir("sharpir", &data); - -SHARPIR Sensor(A0); - +std_msgs::String msg; +ros::Publisher sensor_bme("sensor_bme", &msg); int main() { - float DistanceCM; - nh.initNode(); - nh.advertise(sharpir); - + if (!bme680.begin()) { + printf("BME680 Begin failed \r\n"); + return 1; + } + nh.initNode(); + nh.advertise(sensor_bme); + while (1) { //creates an eternal loop - - DistanceCM=Sensor.cm(); - //sprintf (buffer, "%f", DistanceCM); + char* buffer = (char*) malloc(sizeof(char) * 50); + + bme680.performReading(); + sprintf (buffer, "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)); + - data.data = DistanceCM; - sharpir.publish( &data ); - + msg.data = buffer; + sensor_bme.publish(&msg); + nh.spinOnce(); + free(buffer); wait_ms(1000); + } }