mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_Baro/AP_Baro_MS5611.cpp
This commit is contained in:
parent
46c682454a
commit
bd4f1179b1
|
@ -1,36 +1,36 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
APM_MS5611.cpp - Arduino Library for MS5611-01BA01 absolute pressure sensor
|
||||
Code by Jose Julio, Pat Hickey and Jordi Muñoz. DIYDrones.com
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
Sensor is conected to standard SPI port
|
||||
Chip Select pin: Analog2 (provisional until Jordi defines the pin)!!
|
||||
|
||||
Variables:
|
||||
Temp : Calculated temperature (in Celsius degrees * 100)
|
||||
Press : Calculated pressure (in mbar units * 100)
|
||||
|
||||
|
||||
Methods:
|
||||
init() : Initialization and sensor reset
|
||||
read() : Read sensor data and _calculate Temperature, Pressure
|
||||
This function is optimized so the main host don´t need to wait
|
||||
You can call this function in your main loop
|
||||
Maximum data output frequency 100Hz - this allows maximum oversampling in the chip ADC
|
||||
It returns a 1 if there are new data.
|
||||
get_pressure() : return pressure in mbar*100 units
|
||||
get_temperature() : return temperature in celsius degrees*100 units
|
||||
|
||||
Internal functions:
|
||||
_calculate() : Calculate Temperature and Pressure (temperature compensated) in real units
|
||||
|
||||
|
||||
*/
|
||||
* APM_MS5611.cpp - Arduino Library for MS5611-01BA01 absolute pressure sensor
|
||||
* Code by Jose Julio, Pat Hickey and Jordi Muñoz. DIYDrones.com
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* Sensor is conected to standard SPI port
|
||||
* Chip Select pin: Analog2 (provisional until Jordi defines the pin)!!
|
||||
*
|
||||
* Variables:
|
||||
* Temp : Calculated temperature (in Celsius degrees * 100)
|
||||
* Press : Calculated pressure (in mbar units * 100)
|
||||
*
|
||||
*
|
||||
* Methods:
|
||||
* init() : Initialization and sensor reset
|
||||
* read() : Read sensor data and _calculate Temperature, Pressure
|
||||
* This function is optimized so the main host don´t need to wait
|
||||
* You can call this function in your main loop
|
||||
* Maximum data output frequency 100Hz - this allows maximum oversampling in the chip ADC
|
||||
* It returns a 1 if there are new data.
|
||||
* get_pressure() : return pressure in mbar*100 units
|
||||
* get_temperature() : return temperature in celsius degrees*100 units
|
||||
*
|
||||
* Internal functions:
|
||||
* _calculate() : Calculate Temperature and Pressure (temperature compensated) in real units
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <SPI.h>
|
||||
|
|
Loading…
Reference in New Issue