mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
uncrustify libraries/AP_IMU/IMU.h
This commit is contained in:
parent
a704f06119
commit
4aa6f1d7a3
@ -69,20 +69,26 @@ public:
|
|||||||
///
|
///
|
||||||
/// @returns vector of rotational rates in radians/sec
|
/// @returns vector of rotational rates in radians/sec
|
||||||
///
|
///
|
||||||
Vector3f get_gyro(void) { return _gyro; }
|
Vector3f get_gyro(void) {
|
||||||
|
return _gyro;
|
||||||
|
}
|
||||||
|
|
||||||
/// Fetch the current accelerometer values
|
/// Fetch the current accelerometer values
|
||||||
///
|
///
|
||||||
/// @returns vector of current accelerations in m/s/s
|
/// @returns vector of current accelerations in m/s/s
|
||||||
///
|
///
|
||||||
Vector3f get_accel(void) { return _accel; }
|
Vector3f get_accel(void) {
|
||||||
|
return _accel;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/// return the number of seconds that the last update represents
|
/// return the number of seconds that the last update represents
|
||||||
///
|
///
|
||||||
/// @returns number of seconds
|
/// @returns number of seconds
|
||||||
///
|
///
|
||||||
float get_delta_time(void) { return _sample_time * 1.0e-6; }
|
float get_delta_time(void) {
|
||||||
|
return _sample_time * 1.0e-6;
|
||||||
|
}
|
||||||
|
|
||||||
/// return the maximum gyro drift rate in radians/s/s. This
|
/// return the maximum gyro drift rate in radians/s/s. This
|
||||||
/// depends on what gyro chips are being used
|
/// depends on what gyro chips are being used
|
||||||
|
Loading…
Reference in New Issue
Block a user