uncrustify libraries/AP_IMU/AP_IMU_Shim.h

This commit is contained in:
uncrustify 2012-08-16 23:19:49 -07:00 committed by Pat Hickey
parent 7f57d462d0
commit c8ff85a598

View File

@ -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
//@{
virtual void init(Start_style style = COLD_START,
void (*callback)(unsigned long t) = delay,
void (*flash_leds_cb)(bool on) = 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_gyro(void (*callback)(unsigned long t) = delay,
void (*flash_leds_cb)(bool on) = NULL) {
};
virtual bool update(void) {
bool updated = _updated;
_updated = false;
/// @name IMU protocol
//@{
virtual void init(Start_style style = COLD_START,
void (*callback)(unsigned long t) = delay,
void (*flash_leds_cb)(bool on) = 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_gyro(void (*callback)(unsigned long t) = delay,
void (*flash_leds_cb)(bool on) = NULL) {};
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 ax() { return 0; }
float ay() { return 0; }
float az() { return 0; }
void ax(const int v) { } float gx() {
void ay(const int v) { } return 0;
void az(const int v) { } }
float gy() {
return 0;
}
float gz() {
return 0;
}
float ax() {
return 0;
}
float ay() {
return 0;
}
float az() {
return 0;
}
/// Set the gyro vector. ::update will return void ax(const int v) {
/// true once after this call. }
/// void ay(const int v) {
/// @param v The new gyro vector. }
/// void az(const int v) {
void set_gyro(Vector3f v) { _gyro = v; _updated = true; } }
/// Set the accelerometer vector. ::update will return /// Set the gyro vector. ::update will return
/// true once after this call. /// true once after this call.
/// ///
/// @param v The new accelerometer vector. /// @param v The new gyro vector.
/// ///
void set_accel(Vector3f v) { _accel = v; _updated = true; } void set_gyro(Vector3f v) {
_gyro = v; _updated = true;
}
// dummy save method /// Set the accelerometer vector. ::update will return
void save(void) { } /// 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;
}
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