2016-01-19 21:26:31 -04:00
|
|
|
#pragma once
|
2012-12-19 18:02:34 -04:00
|
|
|
|
2015-10-26 08:04:56 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-01-19 21:26:31 -04:00
|
|
|
|
2012-12-19 18:02:34 -04:00
|
|
|
#include "AP_InertialSensor_UserInteract.h"
|
|
|
|
|
|
|
|
/**
|
|
|
|
* AP_InertialSensor_UserInteract, implemented in terms of a BetterStream.
|
|
|
|
*/
|
2016-01-19 21:26:31 -04:00
|
|
|
class AP_InertialSensor_UserInteractStream : public AP_InertialSensor_UserInteract {
|
2012-12-19 18:02:34 -04:00
|
|
|
public:
|
|
|
|
AP_InertialSensor_UserInteractStream(AP_HAL::BetterStream *s) :
|
|
|
|
_s(s) {}
|
|
|
|
|
2014-08-07 00:09:17 -03:00
|
|
|
bool blocking_read();
|
2015-11-10 13:05:19 -04:00
|
|
|
void printf(const char*, ...) FMT_PRINTF(2, 3);
|
2012-12-19 18:02:34 -04:00
|
|
|
private:
|
|
|
|
AP_HAL::BetterStream *_s;
|
|
|
|
};
|