ArduPlane: make AP_RANGEFINDER_ENABLED remove more code

This commit is contained in:
Peter Barker 2023-11-08 09:23:41 +11:00 committed by Andrew Tridgell
parent f64fcb78d3
commit c14c2d67d4
10 changed files with 51 additions and 3 deletions

View File

@ -81,7 +81,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63),
#endif
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66),
#if AP_RANGEFINDER_ENABLED
SCHED_TASK(read_rangefinder, 50, 100, 78),
#endif
#if AP_ICENGINE_ENABLED
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81),
#endif
@ -750,7 +752,9 @@ float Plane::tecs_hgt_afe(void)
float hgt_afe;
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
hgt_afe = height_above_target();
#if AP_RANGEFINDER_ENABLED
hgt_afe -= rangefinder_correction();
#endif
} else {
// when in normal flight we pass the hgt_afe as relative
// altitude to home
@ -967,7 +971,11 @@ bool Plane::flight_option_enabled(FlightOptions flight_option) const
void Plane::precland_update(void)
{
// alt will be unused if we pass false through as the second parameter:
#if AP_RANGEFINDER_ENABLED
return g2.precland.update(rangefinder_state.height_estimate*100, rangefinder_state.in_range);
#else
return g2.precland.update(0, false);
#endif
}
#endif

View File

@ -114,6 +114,7 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
}
#endif
#if AP_RANGEFINDER_ENABLED
const RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
@ -124,4 +125,5 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
}
}
#endif
}

View File

@ -764,6 +764,7 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(parachute, "CHUTE_", AP_Parachute),
#endif
#if AP_RANGEFINDER_ENABLED
// @Group: RNGFND
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
GOBJECT(rangefinder, "RNGFND", RangeFinder),
@ -774,6 +775,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Values: 0:Disabled,1:Enabled
// @User: Standard
GSCALAR(rangefinder_landing, "RNGFND_LANDING", 0),
#endif
#if AP_TERRAIN_AVAILABLE
// @Group: TERRAIN_

View File

@ -39,7 +39,7 @@
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
#include <SRV_Channel/SRV_Channel.h>
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
#include <AP_RangeFinder/AP_RangeFinder_config.h> // Range finder library
#include <Filter/Filter.h> // Filter library
#include <AP_Camera/AP_Camera.h> // Photo or video camera
#include <AP_Terrain/AP_Terrain.h>
@ -206,7 +206,9 @@ private:
AP_Int8 *flight_modes = &g.flight_mode1;
const uint8_t num_flight_modes = 6;
#if AP_RANGEFINDER_ENABLED
AP_FixedWing::Rangefinder_State rangefinder_state;
#endif
#if AP_RPM_ENABLED
AP_RPM rpm_sensor;
@ -865,9 +867,11 @@ private:
float mission_alt_offset(void);
float height_above_target(void);
float lookahead_adjustment(void);
#if AP_RANGEFINDER_ENABLED
float rangefinder_correction(void);
void rangefinder_height_update(void);
void rangefinder_terrain_correction(float &height);
#endif
void stabilize();
void calc_throttle();
void calc_nav_roll();
@ -1074,8 +1078,10 @@ private:
bool rc_throttle_value_ok(void) const;
bool rc_failsafe_active(void) const;
#if AP_RANGEFINDER_ENABLED
// sensors.cpp
void read_rangefinder(void);
#endif
// system.cpp
void init_ardupilot() override;

View File

@ -115,11 +115,13 @@ int32_t Plane::get_RTL_altitude_cm() const
*/
float Plane::relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available)
{
#if AP_RANGEFINDER_ENABLED
if (use_rangefinder_if_available && rangefinder_state.in_range) {
return rangefinder_state.height_estimate;
}
#endif
#if HAL_QUADPLANE_ENABLED
#if HAL_QUADPLANE_ENABLED && AP_RANGEFINDER_ENABLED
if (use_rangefinder_if_available && quadplane.in_vtol_land_final() &&
rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow) {
// a special case for quadplane landing when rangefinder goes
@ -252,8 +254,10 @@ int32_t Plane::relative_target_altitude_cm(void)
target_altitude.lookahead = lookahead_adjustment();
relative_home_height += target_altitude.lookahead;
#if AP_RANGEFINDER_ENABLED
// correct for rangefinder data
relative_home_height += rangefinder_correction();
#endif
// we are following terrain, and have terrain data for the
// current location. Use it.
@ -262,7 +266,9 @@ int32_t Plane::relative_target_altitude_cm(void)
#endif
int32_t relative_alt = target_altitude.amsl_cm - home.alt;
relative_alt += mission_alt_offset()*100;
#if AP_RANGEFINDER_ENABLED
relative_alt += rangefinder_correction() * 100;
#endif
return relative_alt;
}
@ -608,6 +614,7 @@ float Plane::lookahead_adjustment(void)
}
#if AP_RANGEFINDER_ENABLED
/*
correct target altitude using rangefinder data. Returns offset in
meters to correct target altitude. A positive number means we need
@ -747,6 +754,7 @@ void Plane::rangefinder_height_update(void)
}
}
#endif // AP_RANGEFINDER_ENABLED
/*
determine if Non Auto Terrain Disable is active and allowed in present control mode

View File

@ -255,14 +255,23 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
} else {
// use rangefinder to correct if possible
#if AP_RANGEFINDER_ENABLED
float height = height_above_target() - rangefinder_correction();
#else
float height = height_above_target();
#endif
// for flare calculations we don't want to use the terrain
// correction as otherwise we will flare early on rising
// ground
height -= auto_state.terrain_correction;
return landing.verify_land(prev_WP_loc, next_WP_loc, current_loc,
height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(),
g.rangefinder_landing && rangefinder_state.in_range);
#if AP_RANGEFINDER_ENABLED
g.rangefinder_landing && rangefinder_state.in_range
#else
false
#endif
);
}
case MAV_CMD_NAV_LOITER_UNLIM:
@ -421,8 +430,10 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd)
auto_state.takeoff_pitch_cd = 1000;
}
#if AP_RANGEFINDER_ENABLED
// zero rangefinder state, start to accumulate good samples now
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
#endif
landing.do_land(cmd, relative_altitude);

View File

@ -168,7 +168,9 @@ void Mode::update_target_altitude()
plane.set_target_altitude_location(plane.next_WP_loc);
} else if (plane.landing.is_on_approach()) {
plane.landing.setup_landing_glide_slope(plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.target_altitude.offset_cm);
#if AP_RANGEFINDER_ENABLED
plane.landing.adjust_landing_slope_for_rangefinder_bump(plane.rangefinder_state, plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.auto_state.wp_distance, plane.target_altitude.offset_cm);
#endif
} else if (plane.landing.get_target_altitude_location(target_location)) {
plane.set_target_altitude_location(target_location);
#if HAL_SOARING_ENABLED

View File

@ -3777,7 +3777,11 @@ float QuadPlane::forward_throttle_pct()
// approach the landing point when landing below the takeoff point
vel_forward.last_pct = vel_forward.integrator;
} else if ((in_vtol_land_final() && motors->limit.throttle_lower) ||
#if AP_RANGEFINDER_ENABLED
(plane.g.rangefinder_landing && (plane.rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow))) {
#else
false) {
#endif
// we're in the settling phase of landing or using a rangefinder that is out of range low, disable fwd motor
vel_forward.last_pct = 0;
vel_forward.integrator = 0;

View File

@ -2,6 +2,7 @@
#include <AP_RSSI/AP_RSSI.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#if AP_RANGEFINDER_ENABLED
/*
read the rangefinder and update height estimate
*/
@ -33,3 +34,5 @@ void Plane::read_rangefinder(void)
rangefinder_height_update();
}
#endif // AP_RANGEFINDER_ENABLED

View File

@ -36,9 +36,11 @@ void Plane::init_ardupilot()
// init baro
barometer.init();
#if AP_RANGEFINDER_ENABLED
// initialise rangefinder
rangefinder.set_log_rfnd_bit(MASK_LOG_SONAR);
rangefinder.init(ROTATION_PITCH_270);
#endif
// initialise battery monitoring
battery.init();