int main (void) { bbb_i2c i2c; i2c.open(); ms5611 baro(i2c.fd); while(1) { baro.update(); printf("baro t=%f p0=%f p=%f altimeter=%f\r\n",baro.T,baro.P0,baro.P,baro.H); } return 0; }
int main() { MS5611 baro(MS5611_ADDRESS_CSB_HIGH); baro.initialize(); while (true) { baro.refreshPressure(); usleep(10000); // Waiting for pressure data ready baro.readPressure(); baro.refreshTemperature(); usleep(10000); // Waiting for temperature data ready baro.readTemperature(); baro.calculatePressureAndTemperature(); printf("Temperature(C): %f Pressure(millibar): %f\n", baro.getTemperature(), baro.getPressure()); sleep(1); } return 0; }
/** * @brief Creates an XsOutputConfigurationArray and pushes it to the sensor. * @details * - Configures the sensor with desired modules * - Refer to xsdataidentifier.h */ void mtiG::configure(){ XsOutputConfigurationArray configArray; if(mSettings.orientationData){ //Quaternion - containsOrientation XsOutputConfiguration quat(XDI_Quaternion, mSettings.orientationFreq);// para pedir quaternion configArray.push_back(quat); } if(mSettings.gpsData){ //LATITUDE E LONGITUDE -containsLatitudeLongitude XsOutputConfiguration gps(XDI_LatLon, mSettings.gpsFreq);// para pedir gps, //XDI_Quaternion 06/04 configArray.push_back(gps); XsOutputConfiguration gps_age(XDI_GpsAge, mSettings.gpsFreq);// para pedir gps, //XDI_Quaternion 06/04 configArray.push_back(gps_age); XsOutputConfiguration gps_sol(XDI_GpsSol, mSettings.gpsFreq);// para pedir gps, //XDI_Quaternion 06/04 configArray.push_back(gps_sol); XsOutputConfiguration gps_dop(XDI_GpsDop, mSettings.gpsFreq);// para pedir gps, //XDI_Quaternion 06/04 configArray.push_back(gps_dop); } if(mSettings.temperatureData){ //TEMPERATURA - containsTemperature XsOutputConfiguration temp(XDI_Temperature, mSettings.temperatureFreq); configArray.push_back(temp); } if(mSettings.accelerationData){ //ACCELERATION - containsCalibratedAcceleration XsOutputConfiguration accel(XDI_Acceleration, mSettings.accelerationFreq); configArray.push_back(accel); } if(mSettings.pressureData){ //PRESSURE - containsPressure XsOutputConfiguration baro(XDI_BaroPressure, mSettings.pressureFreq); configArray.push_back(baro); } if(mSettings.magneticData){ //MAGNETIC FIELD - containsCalibratedMagneticField XsOutputConfiguration magnet(XDI_MagneticField, mSettings.magneticFreq); configArray.push_back(magnet); } if(mSettings.altitudeData){ //ALTITUDE - containsAltitude XsOutputConfiguration alt(XDI_AltitudeEllipsoid, mSettings.altitudeFreq); configArray.push_back(alt); } if(mSettings.gyroscopeData){ //GYRO - containsCalibratedGyroscopeData XsOutputConfiguration gyro(XDI_RateOfTurn, mSettings.gyroscopeFreq); configArray.push_back(gyro); } if(mSettings.velocityData){ //VELOCIDADE XYZ XsOutputConfiguration vel_xyz(XDI_VelocityXYZ, mSettings.velocityFreq); configArray.push_back(vel_xyz); } // Puts configArray into the device, overwriting the current configuration if (!device->setOutputConfiguration(configArray)) { throw std::runtime_error("Could not configure MTmk4 device. Aborting."); } }