Plane: disabled rangefinder on APM2
this saves 5k of flash space, enough for support to be kept for another release
This commit is contained in:
parent
6fe65cdd9a
commit
554869033f
@ -266,6 +266,7 @@ void Plane::send_extended_status1(mavlink_channel_t chan)
|
||||
}
|
||||
#endif
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
if (rangefinder.num_sensors() > 0) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
if (g.rangefinder_landing) {
|
||||
@ -275,6 +276,7 @@ void Plane::send_extended_status1(mavlink_channel_t chan)
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (AP_Notify::flags.initialising) {
|
||||
// while initialising the gyros and accels are not enabled
|
||||
@ -456,6 +458,7 @@ void Plane::send_wind(mavlink_channel_t chan)
|
||||
|
||||
void Plane::send_rangefinder(mavlink_channel_t chan)
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
if (!rangefinder.has_data()) {
|
||||
// no sonar to report
|
||||
return;
|
||||
@ -464,6 +467,7 @@ void Plane::send_rangefinder(mavlink_channel_t chan)
|
||||
chan,
|
||||
rangefinder.distance_cm() * 0.01f,
|
||||
rangefinder.voltage_mv()*0.001f);
|
||||
#endif
|
||||
}
|
||||
|
||||
void Plane::send_current_waypoint(mavlink_channel_t chan)
|
||||
|
@ -357,6 +357,7 @@ struct PACKED log_Sonar {
|
||||
// Write a sonar packet
|
||||
void Plane::Log_Write_Sonar()
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
struct log_Sonar pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_SONAR_MSG),
|
||||
timestamp : millis(),
|
||||
@ -369,6 +370,7 @@ void Plane::Log_Write_Sonar()
|
||||
correction : rangefinder_state.correction
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
#endif
|
||||
}
|
||||
|
||||
struct PACKED log_Optflow {
|
||||
|
@ -987,9 +987,11 @@ const AP_Param::Info Plane::var_info[] PROGMEM = {
|
||||
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
||||
GOBJECT(relay, "RELAY_", AP_Relay),
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
// @Group: RNGFND
|
||||
// @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
|
||||
GOBJECT(rangefinder, "RNGFND", RangeFinder),
|
||||
#endif
|
||||
|
||||
// @Param: RNGFND_LANDING
|
||||
// @DisplayName: Enable rangefinder for landing
|
||||
|
@ -233,6 +233,7 @@ private:
|
||||
// a pin for reading the receiver RSSI voltage.
|
||||
AP_HAL::AnalogSource *rssi_analog_source;
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
// rangefinder
|
||||
RangeFinder rangefinder;
|
||||
|
||||
@ -242,6 +243,7 @@ private:
|
||||
uint32_t last_correction_time_ms;
|
||||
uint8_t in_range_count;
|
||||
} rangefinder_state;
|
||||
#endif
|
||||
|
||||
// Relay
|
||||
AP_Relay relay;
|
||||
|
@ -525,6 +525,7 @@ float Plane::lookahead_adjustment(void)
|
||||
*/
|
||||
float Plane::rangefinder_correction(void)
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
if (millis() - rangefinder_state.last_correction_time_ms > 5000) {
|
||||
// we haven't had any rangefinder data for 5s - don't use it
|
||||
return 0;
|
||||
@ -540,9 +541,12 @@ float Plane::rangefinder_correction(void)
|
||||
}
|
||||
|
||||
return rangefinder_state.correction;
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
/*
|
||||
update the offset between rangefinder height and terrain height
|
||||
*/
|
||||
@ -591,3 +595,4 @@ void Plane::rangefinder_height_update(void)
|
||||
rangefinder_state.last_correction_time_ms = millis();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -63,10 +63,10 @@
|
||||
//
|
||||
|
||||
#ifndef FRSKY_TELEM_ENABLED
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
#else
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define FRSKY_TELEM_ENABLED ENABLED
|
||||
#else
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@ -82,6 +82,12 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define RANGEFINDER_ENABLED ENABLED
|
||||
#else
|
||||
# define RANGEFINDER_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RADIO CONFIGURATION
|
||||
|
@ -52,9 +52,14 @@ bool Plane::verify_land()
|
||||
rangefinder data (to prevent us keeping throttle on
|
||||
after landing if we've had positive baro drift)
|
||||
*/
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
bool rangefinder_in_range = rangefinder_state.in_range;
|
||||
#else
|
||||
bool rangefinder_in_range = false;
|
||||
#endif
|
||||
if (height <= g.land_flare_alt ||
|
||||
(aparm.land_flare_sec > 0 && height <= auto_state.land_sink_rate * aparm.land_flare_sec) ||
|
||||
(!rangefinder_state.in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) ||
|
||||
(!rangefinder_in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) ||
|
||||
(fabsf(auto_state.land_sink_rate) < 0.2f && !is_flying())) {
|
||||
|
||||
if (!auto_state.land_complete) {
|
||||
|
@ -12,7 +12,9 @@ void Plane::init_barometer(void)
|
||||
|
||||
void Plane::init_rangefinder(void)
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
rangefinder.init();
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
@ -20,12 +22,14 @@ void Plane::init_rangefinder(void)
|
||||
*/
|
||||
void Plane::read_rangefinder(void)
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
rangefinder.update();
|
||||
|
||||
if (should_log(MASK_LOG_SONAR))
|
||||
Log_Write_Sonar();
|
||||
|
||||
rangefinder_height_update();
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user