mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_InertialSensor/AP_InertialSensor.h
This commit is contained in:
parent
9d7ca3a876
commit
c3de56ba94
|
@ -10,57 +10,58 @@
|
|||
*/
|
||||
class AP_InertialSensor
|
||||
{
|
||||
public:
|
||||
AP_InertialSensor() {}
|
||||
public:
|
||||
AP_InertialSensor() {
|
||||
}
|
||||
|
||||
virtual uint16_t init( AP_PeriodicProcess * scheduler ) = 0;
|
||||
virtual uint16_t init( AP_PeriodicProcess * scheduler ) = 0;
|
||||
|
||||
/* Update the sensor data, so that getters are nonblocking.
|
||||
* Returns a bool of whether data was updated or not.
|
||||
*/
|
||||
virtual bool update() = 0;
|
||||
/* Update the sensor data, so that getters are nonblocking.
|
||||
* Returns a bool of whether data was updated or not.
|
||||
*/
|
||||
virtual bool update() = 0;
|
||||
|
||||
// check if the sensors have new data
|
||||
virtual bool new_data_available(void) = 0;
|
||||
// check if the sensors have new data
|
||||
virtual bool new_data_available(void) = 0;
|
||||
|
||||
/* Getters for individual gyro axes.
|
||||
* Gyros have correct coordinate frame and units (degrees per second).
|
||||
*/
|
||||
virtual float gx() = 0;
|
||||
virtual float gy() = 0;
|
||||
virtual float gz() = 0;
|
||||
/* Getters for individual gyro axes.
|
||||
* Gyros have correct coordinate frame and units (degrees per second).
|
||||
*/
|
||||
virtual float gx() = 0;
|
||||
virtual float gy() = 0;
|
||||
virtual float gz() = 0;
|
||||
|
||||
/* Same data as above gyro getters, written to array as { gx, gy, gz } */
|
||||
virtual void get_gyros( float * ) = 0;
|
||||
/* Same data as above gyro getters, written to array as { gx, gy, gz } */
|
||||
virtual void get_gyros( float * ) = 0;
|
||||
|
||||
/* Getters for individual accel axes.
|
||||
* Accels have correct coordinate frame ( flat level ax, ay = 0; az = -9.81)
|
||||
* and units (meters per second squared).
|
||||
*/
|
||||
virtual float ax() = 0;
|
||||
virtual float ay() = 0;
|
||||
virtual float az() = 0;
|
||||
/* Getters for individual accel axes.
|
||||
* Accels have correct coordinate frame ( flat level ax, ay = 0; az = -9.81)
|
||||
* and units (meters per second squared).
|
||||
*/
|
||||
virtual float ax() = 0;
|
||||
virtual float ay() = 0;
|
||||
virtual float az() = 0;
|
||||
|
||||
/* Same data as above accel getters, written to array as { ax, ay, az } */
|
||||
virtual void get_accels( float * ) = 0;
|
||||
/* Same data as above accel getters, written to array as { ax, ay, az } */
|
||||
virtual void get_accels( float * ) = 0;
|
||||
|
||||
/* Same data as above accel and gyro getters, written to array as
|
||||
* { gx, gy, gz, ax, ay, az }
|
||||
*/
|
||||
virtual void get_sensors( float * ) = 0;
|
||||
/* Same data as above accel and gyro getters, written to array as
|
||||
* { gx, gy, gz, ax, ay, az }
|
||||
*/
|
||||
virtual void get_sensors( float * ) = 0;
|
||||
|
||||
/* Temperature, in degrees celsius, of the gyro. */
|
||||
virtual float temperature() = 0;
|
||||
/* Temperature, in degrees celsius, of the gyro. */
|
||||
virtual float temperature() = 0;
|
||||
|
||||
/* sample_time returns the delta in microseconds since the
|
||||
* last call to reset_sample_time.
|
||||
*/
|
||||
virtual uint32_t sample_time() = 0;
|
||||
virtual void reset_sample_time() = 0;
|
||||
/* sample_time returns the delta in microseconds since the
|
||||
* last call to reset_sample_time.
|
||||
*/
|
||||
virtual uint32_t sample_time() = 0;
|
||||
virtual void reset_sample_time() = 0;
|
||||
|
||||
// return the maximum gyro drift rate in radians/s/s. This
|
||||
// depends on what gyro chips are being used
|
||||
virtual float get_gyro_drift_rate(void) = 0;
|
||||
// return the maximum gyro drift rate in radians/s/s. This
|
||||
// depends on what gyro chips are being used
|
||||
virtual float get_gyro_drift_rate(void) = 0;
|
||||
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue