Browse Source

uncrustify libraries/AP_IMU/AP_IMU_Shim.h

master
uncrustify 13 years ago committed by Pat Hickey
parent
commit
c8ff85a598
  1. 151
      libraries/AP_IMU/AP_IMU_Shim.h

151
libraries/AP_IMU/AP_IMU_Shim.h

@ -11,72 +11,99 @@
class AP_IMU_Shim : public IMU class AP_IMU_Shim : public IMU
{ {
public: public:
AP_IMU_Shim(void) { AP_IMU_Shim(void) {
_product_id = AP_PRODUCT_ID_NONE; _product_id = AP_PRODUCT_ID_NONE;
} }
/// @name IMU protocol /// @name IMU protocol
//@{ //@{
virtual void init(Start_style style = COLD_START, virtual void init(Start_style style = COLD_START,
void (*callback)(unsigned long t) = delay, void (*callback)(unsigned long t) = delay,
void (*flash_leds_cb)(bool on) = NULL, void (*flash_leds_cb)(bool on) = NULL,
AP_PeriodicProcess *scheduler = NULL) {}; AP_PeriodicProcess * scheduler = NULL) {
virtual void init_accel(void (*callback)(unsigned long t) = delay, };
void (*flash_leds_cb)(bool on) = NULL) {}; virtual void init_accel(void (*callback)(unsigned long t) = delay,
virtual void init_gyro(void (*callback)(unsigned long t) = delay, void (*flash_leds_cb)(bool on) = NULL) {
void (*flash_leds_cb)(bool on) = NULL) {}; };
virtual bool update(void) { virtual void init_gyro(void (*callback)(unsigned long t) = delay,
bool updated = _updated; void (*flash_leds_cb)(bool on) = NULL) {
_updated = false; };
virtual bool update(void) {
bool updated = _updated;
_updated = false;
// return number of microseconds since last call // return number of microseconds since last call
uint32_t us = micros(); uint32_t us = micros();
uint32_t ret = us - last_ch6_micros; uint32_t ret = us - last_ch6_micros;
last_ch6_micros = us; last_ch6_micros = us;
_sample_time = ret; _sample_time = ret;
return updated; return updated;
} }
//@} //@}
virtual bool new_data_available(void) { return true; } virtual bool new_data_available(void) {
return true;
float gx() { return 0; } }
float gy() { return 0; }
float gz() { return 0; } float gx() {
float ax() { return 0; } return 0;
float ay() { return 0; } }
float az() { return 0; } float gy() {
return 0;
void ax(const int v) { } }
void ay(const int v) { } float gz() {
void az(const int v) { } return 0;
}
/// Set the gyro vector. ::update will return float ax() {
/// true once after this call. return 0;
/// }
/// @param v The new gyro vector. float ay() {
/// return 0;
void set_gyro(Vector3f v) { _gyro = v; _updated = true; } }
float az() {
/// Set the accelerometer vector. ::update will return return 0;
/// true once after this call. }
///
/// @param v The new accelerometer vector. void ax(const int v) {
/// }
void set_accel(Vector3f v) { _accel = v; _updated = true; } void ay(const int v) {
}
// dummy save method void az(const int v) {
void save(void) { } }
float get_gyro_drift_rate(void) { return 0; } /// Set the gyro vector. ::update will return
/// true once after this call.
///
/// @param v The new gyro vector.
///
void set_gyro(Vector3f v) {
_gyro = v; _updated = true;
}
/// Set the accelerometer vector. ::update will return
/// true once after this call.
///
/// @param v The new accelerometer vector.
///
void set_accel(Vector3f v) {
_accel = v; _updated = true;
}
// dummy save method
void save(void) {
}
float get_gyro_drift_rate(void) {
return 0;
}
private: private:
/// set true when new data is delivered /// set true when new data is delivered
bool _updated; bool _updated;
uint32_t last_ch6_micros; uint32_t last_ch6_micros;
}; };
#endif #endif

Loading…
Cancel
Save