diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 865914316d..33accb17c1 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -24,7 +24,7 @@ //#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash //#define AC_FENCE DISABLED // disable fence to save 2k of flash //#define CAMERA DISABLED // disable camera trigger to save 1k of flash -//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash +//#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash //#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash //#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally) //#define AC_TERRAIN DISABLED // disable terrain library diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index b42c61632f..92b9e2623f 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -169,7 +169,7 @@ private: Compass compass; AP_InertialSensor ins; -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED RangeFinder sonar {serial_manager}; bool sonar_enabled; // enable user switch for sonar #endif diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index af764c63ae..d175af2cc5 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -249,7 +249,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan) } #endif -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED if (sonar.num_sensors() > 0) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; @@ -409,7 +409,7 @@ void NOINLINE Copter::send_current_waypoint(mavlink_channel_t chan) mavlink_msg_mission_current_send(chan, mission.get_current_nav_index()); } -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED void NOINLINE Copter::send_rangefinder(mavlink_channel_t chan) { // exit immediately if sonar is disabled @@ -633,7 +633,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) break; case MSG_RANGEFINDER: -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED CHECK_PAYLOAD_SIZE(RANGEFINDER); copter.send_rangefinder(chan); #endif diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index ccc972d68b..0785673f16 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -895,7 +895,7 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp GOBJECT(sonar, "RNGFND", RangeFinder), diff --git a/ArduCopter/arming_checks.cpp b/ArduCopter/arming_checks.cpp index bb35cc8a8a..0a7775865d 100644 --- a/ArduCopter/arming_checks.cpp +++ b/ArduCopter/arming_checks.cpp @@ -317,7 +317,7 @@ bool Copter::pre_arm_checks(bool display_failure) return false; } - #if CONFIG_SONAR == ENABLED && OPTFLOW == ENABLED + #if RANGEFINDER_ENABLED == ENABLED && OPTFLOW == ENABLED // check range finder if optflow enabled if (optflow.enabled() && !sonar.pre_arm_check()) { if (display_failure) { diff --git a/ArduCopter/config.h b/ArduCopter/config.h index c2c356538b..94075e60cd 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -48,8 +48,8 @@ #endif #if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode - #undef CONFIG_SONAR - #define CONFIG_SONAR DISABLED + #undef RANGEFINDER_ENABLED + #define RANGEFINDER_ENABLED DISABLED #endif #define MAGNETOMETER ENABLED @@ -125,8 +125,8 @@ // Sonar // -#ifndef CONFIG_SONAR - # define CONFIG_SONAR ENABLED +#ifndef RANGEFINDER_ENABLED + # define RANGEFINDER_ENABLED ENABLED #endif #ifndef SONAR_ALT_HEALTH_MAX diff --git a/ArduCopter/control_land.cpp b/ArduCopter/control_land.cpp index 5dd65833b8..e4bb636e1b 100644 --- a/ArduCopter/control_land.cpp +++ b/ArduCopter/control_land.cpp @@ -233,7 +233,7 @@ void Copter::land_nogps_run() // should be called at 100hz or higher float Copter::get_land_descent_speed() { -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED bool sonar_ok = sonar_enabled && (sonar.status() == RangeFinder::RangeFinder_Good); #else bool sonar_ok = false; diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 232d9fda8a..49d5e8537d 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -26,7 +26,7 @@ void Copter::read_barometer(void) motors.set_air_density_ratio(barometer.get_air_density_ratio()); } -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED void Copter::init_sonar(void) { sonar.init(); @@ -36,7 +36,7 @@ void Copter::init_sonar(void) // return sonar altitude in centimeters int16_t Copter::read_sonar(void) { -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED sonar.update(); // exit immediately if sonar is disabled diff --git a/ArduCopter/switches.cpp b/ArduCopter/switches.cpp index 03d95ef899..de733d47ac 100644 --- a/ArduCopter/switches.cpp +++ b/ArduCopter/switches.cpp @@ -347,7 +347,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) case AUXSW_SONAR: // enable or disable the sonar -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED if (ch_flag == AUX_SWITCH_HIGH) { sonar_enabled = true; }else{ diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index e035a0a089..97f8485698 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -257,7 +257,7 @@ void Copter::init_ardupilot() init_barometer(true); // initialise sonar -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED init_sonar(); #endif diff --git a/ArduCopter/terrain.cpp b/ArduCopter/terrain.cpp index 45d91ed90f..b9cf9243d2 100644 --- a/ArduCopter/terrain.cpp +++ b/ArduCopter/terrain.cpp @@ -10,7 +10,7 @@ void Copter::terrain_update() // tell the rangefinder our height, so it can go into power saving // mode if available -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED float height; if (terrain.height_above_terrain(height, true)) { sonar.set_estimated_terrain_height(height); diff --git a/ArduCopter/test.cpp b/ArduCopter/test.cpp index 3bc6e499de..1f5dab70a3 100644 --- a/ArduCopter/test.cpp +++ b/ArduCopter/test.cpp @@ -245,7 +245,7 @@ int8_t Copter::test_shell(uint8_t argc, const Menu::arg *argv) */ int8_t Copter::test_sonar(uint8_t argc, const Menu::arg *argv) { -#if CONFIG_SONAR == ENABLED +#if RANGEFINDER_ENABLED == ENABLED sonar.init(); cliSerial->printf("RangeFinder: %d devices detected\n", sonar.num_sensors());