mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_Airspeed: removed values passed to constructor
This commit is contained in:
parent
fc26d49260
commit
5e19c0cf04
@ -483,7 +483,7 @@ static float current_total1;
|
|||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Airspeed Sensors
|
// Airspeed Sensors
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
AP_Airspeed airspeed(&pitot_analog_source, AIRSPEED_RATIO, AIRSPEED_SENSOR);
|
AP_Airspeed airspeed(&pitot_analog_source);
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Altitude Sensor variables
|
// Altitude Sensor variables
|
||||||
|
@ -115,18 +115,6 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// AIRSPEED_SENSOR
|
|
||||||
// AIRSPEED_RATIO
|
|
||||||
//
|
|
||||||
#ifndef AIRSPEED_SENSOR
|
|
||||||
# define AIRSPEED_SENSOR DISABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef AIRSPEED_RATIO
|
|
||||||
# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// IMU Selection
|
// IMU Selection
|
||||||
//
|
//
|
||||||
|
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = {
|
|||||||
// @DisplayName: Airspeed ratio
|
// @DisplayName: Airspeed ratio
|
||||||
// @Description: Airspeed calibration ratio
|
// @Description: Airspeed calibration ratio
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 0),
|
AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 1.9936),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -13,14 +13,8 @@ class AP_Airspeed
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_Airspeed(AP_AnalogSource *source, float ratio, bool enable) {
|
AP_Airspeed(AP_AnalogSource *source) {
|
||||||
_source = source;
|
_source = source;
|
||||||
_offset.set(0);
|
|
||||||
_ratio.set(ratio);
|
|
||||||
|
|
||||||
// by default enable but don't use the airspeed sensor
|
|
||||||
_use.set(1);
|
|
||||||
_enable.set(enable?1:0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// read the analog source and update _airspeed
|
// read the analog source and update _airspeed
|
||||||
|
Loading…
Reference in New Issue
Block a user