AP_InertialSensor: rename Stub to HIL
more consistent with other drivers
This commit is contained in:
parent
dd081ab23b
commit
cf726c6642
@ -185,7 +185,7 @@ protected:
|
||||
|
||||
#include "AP_InertialSensor_Oilpan.h"
|
||||
#include "AP_InertialSensor_MPU6000.h"
|
||||
#include "AP_InertialSensor_Stub.h"
|
||||
#include "AP_InertialSensor_HIL.h"
|
||||
#include "AP_InertialSensor_PX4.h"
|
||||
#include "AP_InertialSensor_UserInteract_Stream.h"
|
||||
#include "AP_InertialSensor_UserInteract_MAVLink.h"
|
||||
|
@ -1,16 +1,16 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "AP_InertialSensor_Stub.h"
|
||||
#include "AP_InertialSensor_HIL.h"
|
||||
#include <AP_HAL.h>
|
||||
const extern AP_HAL::HAL& hal;
|
||||
|
||||
AP_InertialSensor_Stub::AP_InertialSensor_Stub() : AP_InertialSensor() {
|
||||
AP_InertialSensor_HIL::AP_InertialSensor_HIL() : AP_InertialSensor() {
|
||||
Vector3f accels;
|
||||
accels.z = -GRAVITY_MSS;
|
||||
set_accel(accels);
|
||||
}
|
||||
|
||||
uint16_t AP_InertialSensor_Stub::_init_sensor( Sample_rate sample_rate ) {
|
||||
uint16_t AP_InertialSensor_HIL::_init_sensor( Sample_rate sample_rate ) {
|
||||
switch (sample_rate) {
|
||||
case RATE_50HZ:
|
||||
_sample_period_ms = 20;
|
||||
@ -27,25 +27,25 @@ uint16_t AP_InertialSensor_Stub::_init_sensor( Sample_rate sample_rate ) {
|
||||
|
||||
/*================ AP_INERTIALSENSOR PUBLIC INTERFACE ==================== */
|
||||
|
||||
bool AP_InertialSensor_Stub::update( void ) {
|
||||
bool AP_InertialSensor_HIL::update( void ) {
|
||||
uint32_t now = hal.scheduler->millis();
|
||||
_delta_time_usec = (now - _last_update_ms) * 1000;
|
||||
_last_update_ms = now;
|
||||
return true;
|
||||
}
|
||||
|
||||
float AP_InertialSensor_Stub::get_delta_time() {
|
||||
float AP_InertialSensor_HIL::get_delta_time() {
|
||||
return _delta_time_usec * 1.0e-6;
|
||||
}
|
||||
uint32_t AP_InertialSensor_Stub::get_last_sample_time_micros() {
|
||||
uint32_t AP_InertialSensor_HIL::get_last_sample_time_micros() {
|
||||
return _last_update_ms * 1000;
|
||||
}
|
||||
float AP_InertialSensor_Stub::get_gyro_drift_rate(void) {
|
||||
float AP_InertialSensor_HIL::get_gyro_drift_rate(void) {
|
||||
// 0.5 degrees/second/minute
|
||||
return ToRad(0.5/60);
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_Stub::sample_available()
|
||||
bool AP_InertialSensor_HIL::sample_available()
|
||||
{
|
||||
uint16_t ret = (hal.scheduler->millis() - _last_update_ms)
|
||||
/ _sample_period_ms;
|
@ -6,11 +6,11 @@
|
||||
#include <AP_Progmem.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
class AP_InertialSensor_Stub : public AP_InertialSensor
|
||||
class AP_InertialSensor_HIL : public AP_InertialSensor
|
||||
{
|
||||
public:
|
||||
|
||||
AP_InertialSensor_Stub();
|
||||
AP_InertialSensor_HIL();
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
Loading…
Reference in New Issue
Block a user