@ -15,7 +15,6 @@
@@ -15,7 +15,6 @@
/*
* APM_Airspeed . cpp - airspeed ( pitot ) driver
*/
# include "AP_Airspeed.h"
# include <AP_ADC/AP_ADC.h>
# include <AP_Common/AP_Common.h>
@ -24,16 +23,18 @@
@@ -24,16 +23,18 @@
# include <AP_Math/AP_Math.h>
# include <GCS_MAVLink/GCS.h>
# include <utility>
# include "AP_Airspeed.h"
# include "AP_Airspeed_I2C.h"
# include "AP_Airspeed_analog.h"
extern const AP_HAL : : HAL & hal ;
// the virtual pin for digital airspeed sensors
# define AP_AIRSPEED_I2C_PIN 65
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
# define ARSPD_DEFAULT_TYPE TYPE_ANALOG
# define ARSPD_DEFAULT_PIN 1
# else
# define ARSPD_DEFAULT_PIN AP_AIRSPEED_I2C_PIN
# define ARSPD_DEFAULT_TYPE TYPE_I2C_MS4525
# define ARSPD_DEFAULT_PIN 15
# endif
# if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
@ -47,12 +48,12 @@ extern const AP_HAL::HAL &hal;
@@ -47,12 +48,12 @@ extern const AP_HAL::HAL &hal;
// table of user settable parameters
const AP_Param : : GroupInfo AP_Airspeed : : var_info [ ] = {
// @Param: ENABL E
// @DisplayName: Airspeed enabl e
// @Description: enable airspeed sensor
// @Values: 0:Disable,1:Enable
// @Param: TYP E
// @DisplayName: Airspeed typ e
// @Description: Type of airspeed sensor
// @Values: 0:None,1:I2C-MS4525D0,2:Analog
// @User: Standard
AP_GROUPINFO_FLAGS ( " ENABL E" , 0 , AP_Airspeed , _enable , 1 , AP_PARAM_FLAG_ENABLE ) ,
AP_GROUPINFO_FLAGS ( " TYP E" , 0 , AP_Airspeed , _type , ARSPD_DEFAULT_TYPE , AP_PARAM_FLAG_ENABLE ) ,
// @Param: USE
// @DisplayName: Airspeed use
@ -77,7 +78,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
@@ -77,7 +78,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Param: PIN
// @DisplayName: Airspeed pin
// @Description: The analog pin number that the airspeed sensor is connected to. Set this to 0..9 for the APM2 analog pin s. S et to 64 o n an APM1 for the dedicated air speed p ort on the end of the board. Set to 11 on PX4 for the analog air speed port . Set to 15 on the Pixhawk for the analog airspeed port. Set to 65 on the PX4 or Pixhawk for an EagleTree or MEAS I2C airspeed sensor.
// @Description: The pin number that the airspeed sensor is connected to for analog sensors. Set to 15 on the Pixhawk for the analog airspeed port.
// @User: Advanced
AP_GROUPINFO ( " PIN " , 4 , AP_Airspeed , _pin , ARSPD_DEFAULT_PIN ) ,
@ -127,19 +128,36 @@ AP_Airspeed::AP_Airspeed()
@@ -127,19 +128,36 @@ AP_Airspeed::AP_Airspeed()
void AP_Airspeed : : init ( )
{
// cope with upgrade from old system
if ( _pin . load ( ) & & _pin . get ( ) ! = 65 ) {
_type . set_default ( TYPE_ANALOG ) ;
}
_last_pressure = 0 ;
_calibration . init ( _ratio ) ;
_last_saved_ratio = _ratio ;
_counter = 0 ;
analog . init ( ) ;
digital . init ( ) ;
switch ( ( enum airspeed_type ) _type . get ( ) ) {
case TYPE_NONE :
// nothing to do
break ;
case TYPE_I2C_MS4525 :
sensor = new AP_Airspeed_I2C ( * this ) ;
break ;
case TYPE_ANALOG :
sensor = new AP_Airspeed_Analog ( * this ) ;
break ;
}
if ( sensor & & ! sensor - > init ( ) ) {
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_INFO , " Airspeed init failed " ) ;
}
}
// read the airspeed sensor
float AP_Airspeed : : get_pressure ( void )
{
if ( ! _enable ) {
if ( ! enabled ( ) ) {
return 0 ;
}
if ( _hil_set ) {
@ -147,10 +165,8 @@ float AP_Airspeed::get_pressure(void)
@@ -147,10 +165,8 @@ float AP_Airspeed::get_pressure(void)
return _hil_pressure ;
}
float pressure = 0 ;
if ( _pin = = AP_AIRSPEED_I2C_PIN ) {
_healthy = digital . get_differential_pressure ( pressure ) ;
} else {
_healthy = analog . get_differential_pressure ( pressure ) ;
if ( sensor ) {
_healthy = sensor - > get_differential_pressure ( pressure ) ;
}
return pressure ;
}
@ -158,11 +174,11 @@ float AP_Airspeed::get_pressure(void)
@@ -158,11 +174,11 @@ float AP_Airspeed::get_pressure(void)
// get a temperature reading if possible
bool AP_Airspeed : : get_temperature ( float & temperature )
{
if ( ! _ enable) {
if ( ! enabled ( ) ) {
return false ;
}
if ( _pin = = AP_AIRSPEED_I2C_PIN ) {
return digital . get_temperature ( temperature ) ;
if ( sensor ) {
return sensor - > get_temperature ( temperature ) ;
}
return false ;
}
@ -171,7 +187,7 @@ bool AP_Airspeed::get_temperature(float &temperature)
@@ -171,7 +187,7 @@ bool AP_Airspeed::get_temperature(float &temperature)
// the get_airspeed() interface can be used
void AP_Airspeed : : calibrate ( bool in_startup )
{
if ( ! _ enable) {
if ( ! enabled ( ) ) {
return ;
}
if ( in_startup & & _skip_cal ) {
@ -214,7 +230,7 @@ void AP_Airspeed::update_calibration(float raw_pressure)
@@ -214,7 +230,7 @@ void AP_Airspeed::update_calibration(float raw_pressure)
void AP_Airspeed : : read ( void )
{
float airspeed_pressure ;
if ( ! _ enable) {
if ( ! enabled ( ) ) {
return ;
}
float raw_pressure = get_pressure ( ) ;