![](/media/cache/img/default_profile.jpg.50x50_q85.jpg)
The integration of BME680 sensor with Nucleo board. ROS Enabled
main.cpp@2:816ad5bfa327, 2021-09-28 (annotated)
- Committer:
- zillkhan
- Date:
- Tue Sep 28 12:41:58 2021 +0000
- Revision:
- 2:816ad5bfa327
- Parent:
- 1:ca82df4237eb
final changes
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
Tomas | 0:d94848220e71 | 1 | #include "mbed.h" |
zillkhan | 1:ca82df4237eb | 2 | #include <ros.h> |
zillkhan | 2:816ad5bfa327 | 3 | #include "std_msgs/String.h" |
zillkhan | 2:816ad5bfa327 | 4 | #include "mbed_bme680.h" |
zillkhan | 2:816ad5bfa327 | 5 | |
zillkhan | 2:816ad5bfa327 | 6 | #define I2C_SDA D14 |
zillkhan | 2:816ad5bfa327 | 7 | #define I2C_SCL D15 |
zillkhan | 2:816ad5bfa327 | 8 | |
zillkhan | 2:816ad5bfa327 | 9 | I2C i2c(I2C_SDA, I2C_SCL); // Used inside the BME680 Mbed Lib. |
zillkhan | 2:816ad5bfa327 | 10 | |
zillkhan | 2:816ad5bfa327 | 11 | BME680 bme680(0xEE); |
Tomas | 0:d94848220e71 | 12 | |
zillkhan | 1:ca82df4237eb | 13 | |
zillkhan | 2:816ad5bfa327 | 14 | ros::NodeHandle nh; |
zillkhan | 1:ca82df4237eb | 15 | |
zillkhan | 2:816ad5bfa327 | 16 | std_msgs::String msg; |
zillkhan | 2:816ad5bfa327 | 17 | ros::Publisher sensor_bme("sensor_bme", &msg); |
zillkhan | 1:ca82df4237eb | 18 | |
Tomas | 0:d94848220e71 | 19 | int main() { |
zillkhan | 1:ca82df4237eb | 20 | |
zillkhan | 2:816ad5bfa327 | 21 | if (!bme680.begin()) { |
zillkhan | 2:816ad5bfa327 | 22 | printf("BME680 Begin failed \r\n"); |
zillkhan | 2:816ad5bfa327 | 23 | return 1; |
zillkhan | 2:816ad5bfa327 | 24 | } |
zillkhan | 2:816ad5bfa327 | 25 | nh.initNode(); |
zillkhan | 2:816ad5bfa327 | 26 | nh.advertise(sensor_bme); |
zillkhan | 2:816ad5bfa327 | 27 | |
Tomas | 0:d94848220e71 | 28 | while (1) { //creates an eternal loop |
zillkhan | 2:816ad5bfa327 | 29 | char* buffer = (char*) malloc(sizeof(char) * 50); |
zillkhan | 2:816ad5bfa327 | 30 | |
zillkhan | 2:816ad5bfa327 | 31 | bme680.performReading(); |
zillkhan | 2:816ad5bfa327 | 32 | 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)); |
zillkhan | 2:816ad5bfa327 | 33 | |
zillkhan | 1:ca82df4237eb | 34 | |
zillkhan | 2:816ad5bfa327 | 35 | msg.data = buffer; |
zillkhan | 2:816ad5bfa327 | 36 | sensor_bme.publish(&msg); |
zillkhan | 2:816ad5bfa327 | 37 | |
zillkhan | 1:ca82df4237eb | 38 | nh.spinOnce(); |
zillkhan | 2:816ad5bfa327 | 39 | free(buffer); |
zillkhan | 1:ca82df4237eb | 40 | wait_ms(1000); |
zillkhan | 2:816ad5bfa327 | 41 | |
Tomas | 0:d94848220e71 | 42 | } |
Tomas | 0:d94848220e71 | 43 | } |