Copter: rename CONFIG_SONAR to RANGEFINDER_ENABLE
This commit is contained in:
parent
e0bf08abe0
commit
028946ae9e
@ -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
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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),
|
||||
|
@ -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) {
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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{
|
||||
|
@ -257,7 +257,7 @@ void Copter::init_ardupilot()
|
||||
init_barometer(true);
|
||||
|
||||
// initialise sonar
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
init_sonar();
|
||||
#endif
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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());
|
||||
|
Loading…
Reference in New Issue
Block a user