mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Copter: fix compilation when rtl option is disabled
This commit is contained in:
parent
621fa857b7
commit
b7f5aa7eab
@ -144,6 +144,16 @@ void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(Mode::Number mode)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int16_t AP_Avoidance_Copter::get_altitude_minimum() const
|
||||||
|
{
|
||||||
|
#if MODE_RTL_ENABLED == ENABLED
|
||||||
|
// do not descend if below RTL alt
|
||||||
|
return copter.g.rtl_altitude;
|
||||||
|
#else
|
||||||
|
return 0;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
// check flight mode is avoid_adsb
|
// check flight mode is avoid_adsb
|
||||||
bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change)
|
bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change)
|
||||||
{
|
{
|
||||||
@ -179,8 +189,8 @@ bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle
|
|||||||
velocity_neu.z = copter.wp_nav->get_default_speed_up();
|
velocity_neu.z = copter.wp_nav->get_default_speed_up();
|
||||||
} else {
|
} else {
|
||||||
velocity_neu.z = -copter.wp_nav->get_default_speed_down();
|
velocity_neu.z = -copter.wp_nav->get_default_speed_down();
|
||||||
// do not descend if below RTL alt
|
// do not descend if below minimum altitude
|
||||||
if (copter.current_loc.alt < copter.g.rtl_altitude) {
|
if (copter.current_loc.alt < get_altitude_minimum()) {
|
||||||
velocity_neu.z = 0.0f;
|
velocity_neu.z = 0.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -238,8 +248,8 @@ bool AP_Avoidance_Copter::handle_avoidance_perpendicular(const AP_Avoidance::Obs
|
|||||||
velocity_neu.z *= copter.wp_nav->get_default_speed_up();
|
velocity_neu.z *= copter.wp_nav->get_default_speed_up();
|
||||||
} else {
|
} else {
|
||||||
velocity_neu.z *= copter.wp_nav->get_default_speed_down();
|
velocity_neu.z *= copter.wp_nav->get_default_speed_down();
|
||||||
// do not descend if below RTL alt
|
// do not descend if below minimum altitude
|
||||||
if (copter.current_loc.alt < copter.g.rtl_altitude) {
|
if (copter.current_loc.alt < get_altitude_minimum()) {
|
||||||
velocity_neu.z = 0.0f;
|
velocity_neu.z = 0.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -19,6 +19,9 @@ private:
|
|||||||
// helper function to set modes and always succeed
|
// helper function to set modes and always succeed
|
||||||
void set_mode_else_try_RTL_else_LAND(Mode::Number mode);
|
void set_mode_else_try_RTL_else_LAND(Mode::Number mode);
|
||||||
|
|
||||||
|
// get minimum limit altitude allowed on descend
|
||||||
|
int16_t get_altitude_minimum() const;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// override avoidance handler
|
// override avoidance handler
|
||||||
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;
|
MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user