mirror of https://github.com/ArduPilot/ardupilot
APM: removed the unused sonar code
when we start supporting a sonar we'll add a AP_Sonar library, like AP_Airspeed
This commit is contained in:
parent
2324997e16
commit
cebb67e1df
|
@ -264,7 +264,6 @@ GCS_MAVLINK gcs3;
|
|||
// PITOT selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
ModeFilterInt16_Size5 sonar_mode_filter(2);
|
||||
|
||||
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
|
||||
AP_AnalogSource_ADC pitot_analog_source( &adc,
|
||||
|
@ -273,14 +272,6 @@ AP_AnalogSource_ADC pitot_analog_source( &adc,
|
|||
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN, 4.0);
|
||||
#endif
|
||||
|
||||
#if SONAR_TYPE == MAX_SONAR_XL
|
||||
AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter);
|
||||
#elif SONAR_TYPE == MAX_SONAR_LV
|
||||
// XXX honestly I think these output the same values
|
||||
// If someone knows, can they confirm it?
|
||||
AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter);
|
||||
#endif
|
||||
|
||||
#if RECEIVER_RSSI_PIN != -1
|
||||
AP_AnalogSource_Arduino RSSI_pin(RECEIVER_RSSI_PIN, 0.25);
|
||||
#endif
|
||||
|
@ -483,9 +474,6 @@ AP_Airspeed airspeed(&pitot_analog_source);
|
|||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Altitude Sensor variables
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Altitude from the sonar sensor. Meters. Not yet implemented.
|
||||
static int16_t sonar_alt;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// flight mode specific
|
||||
|
@ -886,7 +874,6 @@ static void medium_loop()
|
|||
// Read altitude from sensors
|
||||
// ------------------
|
||||
update_alt();
|
||||
if(g.sonar_enabled) sonar_alt = sonar.read();
|
||||
|
||||
// altitude smoothing
|
||||
// ------------------
|
||||
|
|
|
@ -341,7 +341,7 @@ static void Log_Write_GPS( int32_t log_Time, int32_t log_Lattitude, int32_t
|
|||
DataFlash.WriteByte(log_NumSats);
|
||||
DataFlash.WriteLong(log_Lattitude);
|
||||
DataFlash.WriteLong(log_Longitude);
|
||||
DataFlash.WriteInt(sonar_alt); // This one is just temporary for testing out sonar in fixed wing
|
||||
DataFlash.WriteInt(0); // was sonar_alt
|
||||
DataFlash.WriteLong(log_mix_alt);
|
||||
DataFlash.WriteLong(log_gps_alt);
|
||||
DataFlash.WriteLong(log_Ground_Speed);
|
||||
|
|
|
@ -334,7 +334,6 @@ public:
|
|||
AP_Float input_voltage;
|
||||
AP_Int32 pack_capacity; // Battery pack capacity less reserve
|
||||
AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 stick_mixing;
|
||||
AP_Int8 rudder_steer;
|
||||
|
||||
|
|
|
@ -525,13 +525,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
GSCALAR(pack_capacity, "BATT_CAPACITY", HIGH_DISCHARGE),
|
||||
GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH", 0),
|
||||
|
||||
// @Param: SONAR_ENABLE
|
||||
// @DisplayName: Enable Sonar
|
||||
// @Description: Setting this to Enabled(1) will enable the sonar. Setting this to Disabled(0) will disable the sonar
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_enabled, "SONAR_ENABLE", SONAR_ENABLED),
|
||||
|
||||
// barometer ground calibration. The GND_ prefix is chosen for
|
||||
// compatibility with previous releases of ArduPlane
|
||||
GOBJECT(barometer, "GND_", AP_Baro),
|
||||
|
|
|
@ -70,7 +70,6 @@
|
|||
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
|
||||
# define CONFIG_RELAY DISABLED
|
||||
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
|
||||
# define MAGNETOMETER ENABLED
|
||||
# ifdef APM2_BETA_HARDWARE
|
||||
|
@ -152,14 +151,6 @@
|
|||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Pitot
|
||||
//
|
||||
|
||||
#ifndef PITOT_ENABLED
|
||||
# define PITOT_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_PITOT_SOURCE
|
||||
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ADC
|
||||
#endif
|
||||
|
@ -173,17 +164,7 @@
|
|||
# define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
|
||||
# endif
|
||||
#else
|
||||
# warning Invalid value for CONFIG_PITOT_SOURCE, disabling airspeed
|
||||
# undef PITOT_ENABLED
|
||||
# define PITOT_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef SONAR_TYPE
|
||||
# define SONAR_TYPE MAX_SONAR_LV // MAX_SONAR_XL,
|
||||
#endif
|
||||
|
||||
#ifndef SONAR_ENABLED
|
||||
#define SONAR_ENABLED DISABLED
|
||||
# warning Invalid value for CONFIG_PITOT_SOURCE
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -207,10 +207,6 @@ enum gcs_severity {
|
|||
#define RELAY_PIN 47
|
||||
|
||||
|
||||
// sonar
|
||||
#define MAX_SONAR_XL 0
|
||||
#define MAX_SONAR_LV 1
|
||||
#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters
|
||||
#define AN4 4
|
||||
#define AN5 5
|
||||
|
||||
|
|
Loading…
Reference in New Issue