AP_Airspeed: initial support for MS4515DO on Disco

This commit is contained in:
Andrew Tridgell 2016-06-08 22:13:53 +10:00
parent e0047d81a2
commit 28d5103435
3 changed files with 21 additions and 8 deletions

View File

@ -21,8 +21,10 @@
#include <AP_ADC/AP_ADC.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS.h>
#include <utility>
extern const AP_HAL::HAL &hal;
@ -122,6 +124,15 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
};
AP_Airspeed::AP_Airspeed(const AP_Vehicle::FixedWing &parms)
: _EAS2TAS(1.0f)
, _calibration(parms)
, analog(_pin)
{
AP_Param::setup_object_defaults(this, var_info);
}
/*
this scaling factor converts from the old system where we used a
0 to 4095 raw ADC value for 0-5V to the new system which gets the

View File

@ -39,13 +39,7 @@ class AP_Airspeed
{
public:
// constructor
AP_Airspeed(const AP_Vehicle::FixedWing &parms)
: _EAS2TAS(1.0f)
, _calibration(parms)
, analog(_pin)
{
AP_Param::setup_object_defaults(this, var_info);
};
AP_Airspeed(const AP_Vehicle::FixedWing &parms);
void init(void);

View File

@ -22,13 +22,21 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_Math/AP_Math.h>
#include <stdio.h>
#include <utility>
extern const AP_HAL::HAL &hal;
#define MS4525D0_I2C_BUS 1
#define MS4525D0_I2C_ADDR 0x28
#ifdef HAL_AIRSPEED_MS4515DO_I2C_BUS
#define MS4525D0_I2C_BUS HAL_AIRSPEED_MS4515DO_I2C_BUS
#else
#define MS4525D0_I2C_BUS 1
#endif
// probe and initialise the sensor
bool AP_Airspeed_I2C::init()
{