mirror of https://github.com/ArduPilot/ardupilot
hil-sensors: added stub libraries for InertialSensor and PeriodicProcess
* Also added dummy ivar to APM_BMP085_hil
This commit is contained in:
parent
1a8a1973a1
commit
48f92c49fa
|
@ -16,6 +16,7 @@ class APM_BMP085_HIL_Class
|
||||||
void Init(int initialiseWireLib = 1, bool purple_hardware=false);
|
void Init(int initialiseWireLib = 1, bool purple_hardware=false);
|
||||||
uint8_t Read();
|
uint8_t Read();
|
||||||
void setHIL(float Temp, float Press);
|
void setHIL(float Temp, float Press);
|
||||||
|
int32_t _offset_press;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -57,5 +57,6 @@ class AP_InertialSensor
|
||||||
|
|
||||||
#include "AP_InertialSensor_Oilpan.h"
|
#include "AP_InertialSensor_Oilpan.h"
|
||||||
#include "AP_InertialSensor_MPU6000.h"
|
#include "AP_InertialSensor_MPU6000.h"
|
||||||
|
#include "AP_InertialSensor_Stub.h"
|
||||||
|
|
||||||
#endif // __AP_INERTIAL_SENSOR_H__
|
#endif // __AP_INERTIAL_SENSOR_H__
|
||||||
|
|
|
@ -0,0 +1,26 @@
|
||||||
|
|
||||||
|
#include "AP_InertialSensor_Stub.h"
|
||||||
|
|
||||||
|
void AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {}
|
||||||
|
|
||||||
|
/*================ AP_INERTIALSENSOR PUBLIC INTERFACE ==================== */
|
||||||
|
|
||||||
|
bool AP_InertialSensor_Stub::update( void ) {}
|
||||||
|
|
||||||
|
|
||||||
|
float AP_InertialSensor_Stub::gx() { return 0.0f; }
|
||||||
|
float AP_InertialSensor_Stub::gy() { return 0.0f; }
|
||||||
|
float AP_InertialSensor_Stub::gz() { return 0.0f; }
|
||||||
|
|
||||||
|
void AP_InertialSensor_Stub::get_gyros( float * g ) { }
|
||||||
|
|
||||||
|
float AP_InertialSensor_Stub::ax() { return 0.0f; }
|
||||||
|
float AP_InertialSensor_Stub::ay() { return 0.0f; }
|
||||||
|
float AP_InertialSensor_Stub::az() { return 0.0f; }
|
||||||
|
|
||||||
|
void AP_InertialSensor_Stub::get_accels( float * a ) {}
|
||||||
|
void AP_InertialSensor_Stub::get_sensors( float * sensors ) {}
|
||||||
|
|
||||||
|
float AP_InertialSensor_Stub::temperature() { return 0.0; }
|
||||||
|
uint32_t AP_InertialSensor_Stub::sample_time() { return 0; }
|
||||||
|
void AP_InertialSensor_Stub::reset_sample_time() {}
|
|
@ -0,0 +1,35 @@
|
||||||
|
|
||||||
|
#ifndef __AP_INERTIAL_SENSOR_STUB_H__
|
||||||
|
#define __AP_INERTIAL_SENSOR_STUB_H__
|
||||||
|
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "../AP_PeriodicProcess/AP_PeriodicProcess.h"
|
||||||
|
#include "AP_InertialSensor.h"
|
||||||
|
|
||||||
|
class AP_InertialSensor_Stub : public AP_InertialSensor
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
AP_InertialSensor_Stub() {}
|
||||||
|
|
||||||
|
void init( AP_PeriodicProcess * scheduler );
|
||||||
|
|
||||||
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
|
bool update();
|
||||||
|
float gx();
|
||||||
|
float gy();
|
||||||
|
float gz();
|
||||||
|
void get_gyros( float * );
|
||||||
|
float ax();
|
||||||
|
float ay();
|
||||||
|
float az();
|
||||||
|
void get_accels( float * );
|
||||||
|
void get_sensors( float * );
|
||||||
|
float temperature();
|
||||||
|
uint32_t sample_time();
|
||||||
|
void reset_sample_time();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // __AP_INERTIAL_SENSOR_STUB_H__
|
|
@ -3,6 +3,7 @@
|
||||||
#define __AP_PERIODIC_PROCESS_H__
|
#define __AP_PERIODIC_PROCESS_H__
|
||||||
|
|
||||||
#include "PeriodicProcess.h"
|
#include "PeriodicProcess.h"
|
||||||
|
#include "AP_PeriodicProcessStub.h"
|
||||||
#include "AP_TimerProcess.h"
|
#include "AP_TimerProcess.h"
|
||||||
#include "AP_TimerAperiodicProcess.h"
|
#include "AP_TimerAperiodicProcess.h"
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,6 @@
|
||||||
|
|
||||||
|
#include "AP_PeriodicProcessStub.h"
|
||||||
|
AP_PeriodicProcessStub::AP_PeriodicProcessStub(int period) {}
|
||||||
|
void AP_PeriodicProcessStub::init( Arduino_Mega_ISR_Registry * isr_reg ){}
|
||||||
|
void AP_PeriodicProcessStub::register_process(void (*proc)(void) ) {}
|
||||||
|
void AP_PeriodicProcessStub::run(void) {}
|
|
@ -0,0 +1,21 @@
|
||||||
|
|
||||||
|
#ifndef __AP_PERIODIC_PROCESS_STUB_H__
|
||||||
|
#define __AP_PERIODIC_PROCESS_STUB_H__
|
||||||
|
|
||||||
|
#include "PeriodicProcess.h"
|
||||||
|
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
|
||||||
|
|
||||||
|
|
||||||
|
class AP_PeriodicProcessStub : public AP_PeriodicProcess
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
AP_PeriodicProcessStub(int period = 0);
|
||||||
|
void init( Arduino_Mega_ISR_Registry * isr_reg );
|
||||||
|
void register_process(void (* proc)(void));
|
||||||
|
static void run(void);
|
||||||
|
protected:
|
||||||
|
static int _period;
|
||||||
|
static void (*_proc)(void);
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
Loading…
Reference in New Issue