mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_InertialSensor: start implementing UserInteract
* untested implementation in terms of BetterStream
This commit is contained in:
parent
b2d69e6a8c
commit
a2cf47e769
@ -11,7 +11,7 @@
|
||||
#include <stdint.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Math.h>
|
||||
|
||||
#include "AP_InertialSensor_UserInteract.h"
|
||||
/* AP_InertialSensor is an abstraction for gyro and accel measurements
|
||||
* which are correctly aligned to the body axes and scaled to SI units.
|
||||
*
|
||||
|
16
libraries/AP_InertialSensor/AP_InertialSensor_UserInteract.h
Normal file
16
libraries/AP_InertialSensor/AP_InertialSensor_UserInteract.h
Normal file
@ -0,0 +1,16 @@
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_H__
|
||||
#define __AP_INERTIAL_SENSOR_USER_INTERACT_H__
|
||||
|
||||
#include <AP_Progmem.h>
|
||||
|
||||
/* Pure virtual interface class */
|
||||
class AP_InertialSensor_UserInteract {
|
||||
public:
|
||||
virtual uint8_t blocking_read() = 0;
|
||||
virtual void println_P(const prog_char_t *) = 0;
|
||||
virtual void _printf_P(const prog_char *, ...) = 0;
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_USER_INTERACT_H__
|
||||
|
@ -0,0 +1,32 @@
|
||||
#include <stdarg.h>
|
||||
#include <AP_HAL.h>
|
||||
#include "AP_InertialSensor_UserInteract_Stream.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
uint8_t AP_InertialSensor_UserInteractStream::blocking_read() {
|
||||
/* Wait for input to be available */
|
||||
while(!_s->available()) {
|
||||
hal.scheduler->delay(20);
|
||||
}
|
||||
/* Grab first character */
|
||||
uint8_t ret = (uint8_t) _s->read();
|
||||
/* Clear all available input */
|
||||
while (_s->available()) {
|
||||
_s->read();
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_UserInteractStream::println_P(const prog_char_t* str) {
|
||||
_s->println_P(str);
|
||||
}
|
||||
|
||||
void AP_InertialSensor_UserInteractStream::_printf_P(
|
||||
const prog_char* fmt, ...) {
|
||||
va_list ap;
|
||||
va_start(ap, fmt);
|
||||
_s->vprintf_P(fmt, ap);
|
||||
va_end(ap);
|
||||
}
|
||||
|
@ -0,0 +1,25 @@
|
||||
|
||||
#ifndef __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
|
||||
#define __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include "AP_InertialSensor_UserInteract.h"
|
||||
|
||||
/**
|
||||
* AP_InertialSensor_UserInteract, implemented in terms of a BetterStream.
|
||||
*/
|
||||
class AP_InertialSensor_UserInteractStream :
|
||||
public AP_InertialSensor_UserInteract {
|
||||
public:
|
||||
AP_InertialSensor_UserInteractStream(AP_HAL::BetterStream *s) :
|
||||
_s(s) {}
|
||||
|
||||
uint8_t blocking_read();
|
||||
void println_P(const prog_char_t *);
|
||||
void _printf_P(const prog_char *, ...);
|
||||
private:
|
||||
AP_HAL::BetterStream *_s;
|
||||
};
|
||||
|
||||
#endif // __AP_INERTIAL_SENSOR_USER_INTERACT_STREAM_H__
|
||||
|
Loading…
Reference in New Issue
Block a user