|
|
|
@ -8,13 +8,13 @@
@@ -8,13 +8,13 @@
|
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
// rtl_init - initialise rtl controller
|
|
|
|
|
bool Copter::rtl_init(bool ignore_checks) |
|
|
|
|
bool Copter::FlightMode_RTL::init(bool ignore_checks) |
|
|
|
|
{ |
|
|
|
|
if (position_ok() || ignore_checks) { |
|
|
|
|
if (_copter.position_ok() || ignore_checks) { |
|
|
|
|
// initialise waypoint and spline controller
|
|
|
|
|
wp_nav->wp_and_spline_init(); |
|
|
|
|
rtl_build_path(!failsafe.terrain); |
|
|
|
|
rtl_climb_start(); |
|
|
|
|
build_path(!_copter.failsafe.terrain); |
|
|
|
|
climb_start(); |
|
|
|
|
return true; |
|
|
|
|
}else{ |
|
|
|
|
return false; |
|
|
|
@ -22,35 +22,35 @@ bool Copter::rtl_init(bool ignore_checks)
@@ -22,35 +22,35 @@ bool Copter::rtl_init(bool ignore_checks)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// re-start RTL with terrain following disabled
|
|
|
|
|
void Copter::rtl_restart_without_terrain() |
|
|
|
|
void Copter::FlightMode_RTL::restart_without_terrain() |
|
|
|
|
{ |
|
|
|
|
// log an error
|
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_RESTARTED_RTL); |
|
|
|
|
_copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_RESTARTED_RTL); |
|
|
|
|
if (rtl_path.terrain_used) { |
|
|
|
|
rtl_build_path(false); |
|
|
|
|
rtl_climb_start(); |
|
|
|
|
build_path(false); |
|
|
|
|
climb_start(); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing"); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_run - runs the return-to-launch controller
|
|
|
|
|
// should be called at 100hz or more
|
|
|
|
|
void Copter::rtl_run(bool disarm_on_land) |
|
|
|
|
void Copter::FlightMode_RTL::run(bool disarm_on_land) |
|
|
|
|
{ |
|
|
|
|
// check if we need to move to next state
|
|
|
|
|
if (rtl_state_complete) { |
|
|
|
|
switch (rtl_state) { |
|
|
|
|
if (_state_complete) { |
|
|
|
|
switch (_state) { |
|
|
|
|
case RTL_InitialClimb: |
|
|
|
|
rtl_return_start(); |
|
|
|
|
return_start(); |
|
|
|
|
break; |
|
|
|
|
case RTL_ReturnHome: |
|
|
|
|
rtl_loiterathome_start(); |
|
|
|
|
loiterathome_start(); |
|
|
|
|
break; |
|
|
|
|
case RTL_LoiterAtHome: |
|
|
|
|
if (rtl_path.land || failsafe.radio) { |
|
|
|
|
rtl_land_start(); |
|
|
|
|
if (rtl_path.land || _copter.failsafe.radio) { |
|
|
|
|
land_start(); |
|
|
|
|
}else{ |
|
|
|
|
rtl_descent_start(); |
|
|
|
|
descent_start(); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case RTL_FinalDescent: |
|
|
|
@ -63,35 +63,35 @@ void Copter::rtl_run(bool disarm_on_land)
@@ -63,35 +63,35 @@ void Copter::rtl_run(bool disarm_on_land)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// call the correct run function
|
|
|
|
|
switch (rtl_state) { |
|
|
|
|
switch (_state) { |
|
|
|
|
|
|
|
|
|
case RTL_InitialClimb: |
|
|
|
|
rtl_climb_return_run(); |
|
|
|
|
climb_return_run(); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case RTL_ReturnHome: |
|
|
|
|
rtl_climb_return_run(); |
|
|
|
|
climb_return_run(); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case RTL_LoiterAtHome: |
|
|
|
|
rtl_loiterathome_run(); |
|
|
|
|
loiterathome_run(); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case RTL_FinalDescent: |
|
|
|
|
rtl_descent_run(); |
|
|
|
|
descent_run(); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case RTL_Land: |
|
|
|
|
rtl_land_run(disarm_on_land); |
|
|
|
|
land_run(disarm_on_land); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_climb_start - initialise climb to RTL altitude
|
|
|
|
|
void Copter::rtl_climb_start() |
|
|
|
|
void Copter::FlightMode_RTL::climb_start() |
|
|
|
|
{ |
|
|
|
|
rtl_state = RTL_InitialClimb; |
|
|
|
|
rtl_state_complete = false; |
|
|
|
|
_state = RTL_InitialClimb; |
|
|
|
|
_state_complete = false; |
|
|
|
|
|
|
|
|
|
// RTL_SPEED == 0 means use WPNAV_SPEED
|
|
|
|
|
if (g.rtl_speed_cms != 0) { |
|
|
|
@ -101,8 +101,8 @@ void Copter::rtl_climb_start()
@@ -101,8 +101,8 @@ void Copter::rtl_climb_start()
|
|
|
|
|
// set the destination
|
|
|
|
|
if (!wp_nav->set_wp_destination(rtl_path.climb_target)) { |
|
|
|
|
// this should not happen because rtl_build_path will have checked terrain data was available
|
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_TO_SET_DESTINATION); |
|
|
|
|
set_mode(LAND, MODE_REASON_TERRAIN_FAILSAFE); |
|
|
|
|
_copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_TO_SET_DESTINATION); |
|
|
|
|
_copter.set_mode(LAND, MODE_REASON_TERRAIN_FAILSAFE); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
wp_nav->set_fast_waypoint(true); |
|
|
|
@ -112,23 +112,23 @@ void Copter::rtl_climb_start()
@@ -112,23 +112,23 @@ void Copter::rtl_climb_start()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_return_start - initialise return to home
|
|
|
|
|
void Copter::rtl_return_start() |
|
|
|
|
void Copter::FlightMode_RTL::return_start() |
|
|
|
|
{ |
|
|
|
|
rtl_state = RTL_ReturnHome; |
|
|
|
|
rtl_state_complete = false; |
|
|
|
|
_state = RTL_ReturnHome; |
|
|
|
|
_state_complete = false; |
|
|
|
|
|
|
|
|
|
if (!wp_nav->set_wp_destination(rtl_path.return_target)) { |
|
|
|
|
// failure must be caused by missing terrain data, restart RTL
|
|
|
|
|
rtl_restart_without_terrain(); |
|
|
|
|
restart_without_terrain(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// initialise yaw to point home (maybe)
|
|
|
|
|
set_auto_yaw_mode(get_default_auto_yaw_mode(true)); |
|
|
|
|
set_auto_yaw_mode(_copter.get_default_auto_yaw_mode(true)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_climb_return_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
|
|
|
|
|
// called by rtl_run at 100hz or more
|
|
|
|
|
void Copter::rtl_climb_return_run() |
|
|
|
|
void Copter::FlightMode_RTL::climb_return_run() |
|
|
|
|
{ |
|
|
|
|
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
|
|
|
|
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) { |
|
|
|
@ -148,7 +148,7 @@ void Copter::rtl_climb_return_run()
@@ -148,7 +148,7 @@ void Copter::rtl_climb_return_run()
|
|
|
|
|
|
|
|
|
|
// process pilot's yaw input
|
|
|
|
|
float target_yaw_rate = 0; |
|
|
|
|
if (!failsafe.radio) { |
|
|
|
|
if (!_copter.failsafe.radio) { |
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); |
|
|
|
|
if (!is_zero(target_yaw_rate)) { |
|
|
|
@ -160,13 +160,13 @@ void Copter::rtl_climb_return_run()
@@ -160,13 +160,13 @@ void Copter::rtl_climb_return_run()
|
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
// run waypoint controller
|
|
|
|
|
failsafe_terrain_set_status(wp_nav->update_wpnav()); |
|
|
|
|
_copter.failsafe_terrain_set_status(wp_nav->update_wpnav()); |
|
|
|
|
|
|
|
|
|
// call z-axis position controller (wpnav should have already updated it's alt target)
|
|
|
|
|
pos_control->update_z_controller(); |
|
|
|
|
|
|
|
|
|
// call attitude controller
|
|
|
|
|
if (auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
if (_copter.auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain()); |
|
|
|
|
}else{ |
|
|
|
@ -175,18 +175,18 @@ void Copter::rtl_climb_return_run()
@@ -175,18 +175,18 @@ void Copter::rtl_climb_return_run()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check if we've completed this stage of RTL
|
|
|
|
|
rtl_state_complete = wp_nav->reached_wp_destination(); |
|
|
|
|
_state_complete = wp_nav->reached_wp_destination(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_loiterathome_start - initialise return to home
|
|
|
|
|
void Copter::rtl_loiterathome_start() |
|
|
|
|
void Copter::FlightMode_RTL::loiterathome_start() |
|
|
|
|
{ |
|
|
|
|
rtl_state = RTL_LoiterAtHome; |
|
|
|
|
rtl_state_complete = false; |
|
|
|
|
rtl_loiter_start_time = millis(); |
|
|
|
|
_state = RTL_LoiterAtHome; |
|
|
|
|
_state_complete = false; |
|
|
|
|
_loiter_start_time = millis(); |
|
|
|
|
|
|
|
|
|
// yaw back to initial take-off heading yaw unless pilot has already overridden yaw
|
|
|
|
|
if(get_default_auto_yaw_mode(true) != AUTO_YAW_HOLD) { |
|
|
|
|
if(_copter.get_default_auto_yaw_mode(true) != AUTO_YAW_HOLD) { |
|
|
|
|
set_auto_yaw_mode(AUTO_YAW_RESETTOARMEDYAW); |
|
|
|
|
} else { |
|
|
|
|
set_auto_yaw_mode(AUTO_YAW_HOLD); |
|
|
|
@ -195,7 +195,7 @@ void Copter::rtl_loiterathome_start()
@@ -195,7 +195,7 @@ void Copter::rtl_loiterathome_start()
|
|
|
|
|
|
|
|
|
|
// rtl_climb_return_descent_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
|
|
|
|
|
// called by rtl_run at 100hz or more
|
|
|
|
|
void Copter::rtl_loiterathome_run() |
|
|
|
|
void Copter::FlightMode_RTL::loiterathome_run() |
|
|
|
|
{ |
|
|
|
|
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
|
|
|
|
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) { |
|
|
|
@ -215,7 +215,7 @@ void Copter::rtl_loiterathome_run()
@@ -215,7 +215,7 @@ void Copter::rtl_loiterathome_run()
|
|
|
|
|
|
|
|
|
|
// process pilot's yaw input
|
|
|
|
|
float target_yaw_rate = 0; |
|
|
|
|
if (!failsafe.radio) { |
|
|
|
|
if (!_copter.failsafe.radio) { |
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); |
|
|
|
|
if (!is_zero(target_yaw_rate)) { |
|
|
|
@ -227,13 +227,13 @@ void Copter::rtl_loiterathome_run()
@@ -227,13 +227,13 @@ void Copter::rtl_loiterathome_run()
|
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
// run waypoint controller
|
|
|
|
|
failsafe_terrain_set_status(wp_nav->update_wpnav()); |
|
|
|
|
_copter.failsafe_terrain_set_status(wp_nav->update_wpnav()); |
|
|
|
|
|
|
|
|
|
// call z-axis position controller (wpnav should have already updated it's alt target)
|
|
|
|
|
pos_control->update_z_controller(); |
|
|
|
|
|
|
|
|
|
// call attitude controller
|
|
|
|
|
if (auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
if (_copter.auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain()); |
|
|
|
|
}else{ |
|
|
|
@ -242,24 +242,24 @@ void Copter::rtl_loiterathome_run()
@@ -242,24 +242,24 @@ void Copter::rtl_loiterathome_run()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check if we've completed this stage of RTL
|
|
|
|
|
if ((millis() - rtl_loiter_start_time) >= (uint32_t)g.rtl_loiter_time.get()) { |
|
|
|
|
if (auto_yaw_mode == AUTO_YAW_RESETTOARMEDYAW) { |
|
|
|
|
if ((millis() - _loiter_start_time) >= (uint32_t)g.rtl_loiter_time.get()) { |
|
|
|
|
if (_copter.auto_yaw_mode == AUTO_YAW_RESETTOARMEDYAW) { |
|
|
|
|
// check if heading is within 2 degrees of heading when vehicle was armed
|
|
|
|
|
if (labs(wrap_180_cd(ahrs.yaw_sensor-initial_armed_bearing)) <= 200) { |
|
|
|
|
rtl_state_complete = true; |
|
|
|
|
if (labs(wrap_180_cd(ahrs.yaw_sensor-_copter.initial_armed_bearing)) <= 200) { |
|
|
|
|
_state_complete = true; |
|
|
|
|
} |
|
|
|
|
} else { |
|
|
|
|
// we have loitered long enough
|
|
|
|
|
rtl_state_complete = true; |
|
|
|
|
_state_complete = true; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_descent_start - initialise descent to final alt
|
|
|
|
|
void Copter::rtl_descent_start() |
|
|
|
|
void Copter::FlightMode_RTL::descent_start() |
|
|
|
|
{ |
|
|
|
|
rtl_state = RTL_FinalDescent; |
|
|
|
|
rtl_state_complete = false; |
|
|
|
|
_state = RTL_FinalDescent; |
|
|
|
|
_state_complete = false; |
|
|
|
|
|
|
|
|
|
// Set wp navigation target to above home
|
|
|
|
|
wp_nav->init_loiter_target(wp_nav->get_wp_destination()); |
|
|
|
@ -273,7 +273,7 @@ void Copter::rtl_descent_start()
@@ -273,7 +273,7 @@ void Copter::rtl_descent_start()
|
|
|
|
|
|
|
|
|
|
// rtl_descent_run - implements the final descent to the RTL_ALT
|
|
|
|
|
// called by rtl_run at 100hz or more
|
|
|
|
|
void Copter::rtl_descent_run() |
|
|
|
|
void Copter::FlightMode_RTL::descent_run() |
|
|
|
|
{ |
|
|
|
|
int16_t roll_control = 0, pitch_control = 0; |
|
|
|
|
float target_yaw_rate = 0; |
|
|
|
@ -295,12 +295,12 @@ void Copter::rtl_descent_run()
@@ -295,12 +295,12 @@ void Copter::rtl_descent_run()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// process pilot's input
|
|
|
|
|
if (!failsafe.radio) { |
|
|
|
|
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ |
|
|
|
|
if (!_copter.failsafe.radio) { |
|
|
|
|
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && _copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ |
|
|
|
|
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT); |
|
|
|
|
// exit land if throttle is high
|
|
|
|
|
if (!set_mode(LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) { |
|
|
|
|
set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE); |
|
|
|
|
if (!_copter.set_mode(LOITER, MODE_REASON_THROTTLE_LAND_ESCAPE)) { |
|
|
|
|
_copter.set_mode(ALT_HOLD, MODE_REASON_THROTTLE_LAND_ESCAPE); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -334,14 +334,14 @@ void Copter::rtl_descent_run()
@@ -334,14 +334,14 @@ void Copter::rtl_descent_run()
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain()); |
|
|
|
|
|
|
|
|
|
// check if we've reached within 20cm of final altitude
|
|
|
|
|
rtl_state_complete = labs(rtl_path.descent_target.alt - current_loc.alt) < 20; |
|
|
|
|
_state_complete = labs(rtl_path.descent_target.alt - _copter.current_loc.alt) < 20; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_loiterathome_start - initialise controllers to loiter over home
|
|
|
|
|
void Copter::rtl_land_start() |
|
|
|
|
void Copter::FlightMode_RTL::land_start() |
|
|
|
|
{ |
|
|
|
|
rtl_state = RTL_Land; |
|
|
|
|
rtl_state_complete = false; |
|
|
|
|
_state = RTL_Land; |
|
|
|
|
_state_complete = false; |
|
|
|
|
|
|
|
|
|
// Set wp navigation target to above home
|
|
|
|
|
wp_nav->init_loiter_target(wp_nav->get_wp_destination()); |
|
|
|
@ -356,9 +356,22 @@ void Copter::rtl_land_start()
@@ -356,9 +356,22 @@ void Copter::rtl_land_start()
|
|
|
|
|
set_auto_yaw_mode(AUTO_YAW_HOLD); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool Copter::FlightMode_RTL::landing_gear_should_be_deployed() |
|
|
|
|
{ |
|
|
|
|
switch(_state) { |
|
|
|
|
case RTL_LoiterAtHome: |
|
|
|
|
case RTL_Land: |
|
|
|
|
case RTL_FinalDescent: |
|
|
|
|
return true; |
|
|
|
|
default: |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// rtl_returnhome_run - return home
|
|
|
|
|
// called by rtl_run at 100hz or more
|
|
|
|
|
void Copter::rtl_land_run(bool disarm_on_land) |
|
|
|
|
void Copter::FlightMode_RTL::land_run(bool disarm_on_land) |
|
|
|
|
{ |
|
|
|
|
// if not auto armed or landing completed or motor interlock not enabled set throttle to zero and exit immediately
|
|
|
|
|
if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) { |
|
|
|
@ -376,25 +389,25 @@ void Copter::rtl_land_run(bool disarm_on_land)
@@ -376,25 +389,25 @@ void Copter::rtl_land_run(bool disarm_on_land)
|
|
|
|
|
|
|
|
|
|
// disarm when the landing detector says we've landed
|
|
|
|
|
if (ap.land_complete && disarm_on_land) { |
|
|
|
|
init_disarm_motors(); |
|
|
|
|
_copter.init_disarm_motors(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check if we've completed this stage of RTL
|
|
|
|
|
rtl_state_complete = ap.land_complete; |
|
|
|
|
_state_complete = ap.land_complete; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// set motors to full range
|
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
land_run_horizontal_control(); |
|
|
|
|
land_run_vertical_control(); |
|
|
|
|
_copter.land_run_horizontal_control(); |
|
|
|
|
_copter.land_run_vertical_control(); |
|
|
|
|
|
|
|
|
|
// check if we've completed this stage of RTL
|
|
|
|
|
rtl_state_complete = ap.land_complete; |
|
|
|
|
_state_complete = ap.land_complete; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Copter::rtl_build_path(bool terrain_following_allowed) |
|
|
|
|
void Copter::FlightMode_RTL::build_path(bool terrain_following_allowed) |
|
|
|
|
{ |
|
|
|
|
// origin point is our stopping point
|
|
|
|
|
Vector3f stopping_point; |
|
|
|
@ -404,7 +417,7 @@ void Copter::rtl_build_path(bool terrain_following_allowed)
@@ -404,7 +417,7 @@ void Copter::rtl_build_path(bool terrain_following_allowed)
|
|
|
|
|
rtl_path.origin_point.change_alt_frame(Location_Class::ALT_FRAME_ABOVE_HOME); |
|
|
|
|
|
|
|
|
|
// compute return target
|
|
|
|
|
rtl_compute_return_target(terrain_following_allowed); |
|
|
|
|
compute_return_target(terrain_following_allowed); |
|
|
|
|
|
|
|
|
|
// climb target is above our origin point at the return altitude
|
|
|
|
|
rtl_path.climb_target = Location_Class(rtl_path.origin_point.lat, rtl_path.origin_point.lng, rtl_path.return_target.alt, rtl_path.return_target.get_alt_frame()); |
|
|
|
@ -419,28 +432,28 @@ void Copter::rtl_build_path(bool terrain_following_allowed)
@@ -419,28 +432,28 @@ void Copter::rtl_build_path(bool terrain_following_allowed)
|
|
|
|
|
// compute the return target - home or rally point
|
|
|
|
|
// return altitude in cm above home at which vehicle should return home
|
|
|
|
|
// return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set)
|
|
|
|
|
void Copter::rtl_compute_return_target(bool terrain_following_allowed) |
|
|
|
|
void Copter::FlightMode_RTL::compute_return_target(bool terrain_following_allowed) |
|
|
|
|
{ |
|
|
|
|
// set return target to nearest rally point or home position (Note: alt is absolute)
|
|
|
|
|
#if AC_RALLY == ENABLED |
|
|
|
|
rtl_path.return_target = rally.calc_best_rally_or_home_location(current_loc, ahrs.get_home().alt); |
|
|
|
|
rtl_path.return_target = _copter.rally.calc_best_rally_or_home_location(_copter.current_loc, ahrs.get_home().alt); |
|
|
|
|
#else |
|
|
|
|
rtl_path.return_target = ahrs.get_home(); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// curr_alt is current altitude above home or above terrain depending upon use_terrain
|
|
|
|
|
int32_t curr_alt = current_loc.alt; |
|
|
|
|
int32_t curr_alt = _copter.current_loc.alt; |
|
|
|
|
|
|
|
|
|
// decide if we should use terrain altitudes
|
|
|
|
|
rtl_path.terrain_used = terrain_use() && terrain_following_allowed; |
|
|
|
|
rtl_path.terrain_used = _copter.terrain_use() && terrain_following_allowed; |
|
|
|
|
if (rtl_path.terrain_used) { |
|
|
|
|
// attempt to retrieve terrain alt for current location, stopping point and origin
|
|
|
|
|
int32_t origin_terr_alt, return_target_terr_alt; |
|
|
|
|
if (!rtl_path.origin_point.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, origin_terr_alt) || |
|
|
|
|
!rtl_path.return_target.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, return_target_terr_alt) || |
|
|
|
|
!current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, curr_alt)) { |
|
|
|
|
!_copter.current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, curr_alt)) { |
|
|
|
|
rtl_path.terrain_used = false; |
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_TERRAIN, ERROR_CODE_MISSING_TERRAIN_DATA); |
|
|
|
|
_copter.Log_Write_Error(ERROR_SUBSYSTEM_TERRAIN, ERROR_CODE_MISSING_TERRAIN_DATA); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -478,10 +491,10 @@ void Copter::rtl_compute_return_target(bool terrain_following_allowed)
@@ -478,10 +491,10 @@ void Copter::rtl_compute_return_target(bool terrain_following_allowed)
|
|
|
|
|
// if terrain altitudes are being used, the code below which reduces the return_target's altitude can lead to
|
|
|
|
|
// the vehicle not climbing at all as RTL begins. This can be overly conservative and it might be better
|
|
|
|
|
// to apply the fence alt limit independently on the origin_point and return_target
|
|
|
|
|
if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) { |
|
|
|
|
if ((_copter.fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) { |
|
|
|
|
// get return target as alt-above-home so it can be compared to fence's alt
|
|
|
|
|
if (rtl_path.return_target.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_HOME, target_alt)) { |
|
|
|
|
float fence_alt = fence.get_safe_alt_max()*100.0f; |
|
|
|
|
float fence_alt = _copter.fence.get_safe_alt_max()*100.0f; |
|
|
|
|
if (target_alt > fence_alt) { |
|
|
|
|
// reduce target alt to the fence alt
|
|
|
|
|
rtl_path.return_target.alt -= (target_alt - fence_alt); |
|
|
|
|