ardupilot/ArduCopter/mode_smart_rtl.cpp

154 lines
5.2 KiB
C++
Raw Normal View History

2017-07-26 14:14:40 -03:00
#include "Copter.h"
#if MODE_SMARTRTL_ENABLED == ENABLED
2017-07-26 14:14:40 -03:00
/*
2017-09-08 23:45:31 -03:00
* Init and run calls for Smart_RTL flight mode
2017-07-26 14:14:40 -03:00
*
* This code uses the SmartRTL path that is already in memory, and feeds it into WPNav, one point at a time.
2017-07-26 14:14:40 -03:00
* Once the copter is close to home, it will run a standard land controller.
*/
bool Copter::ModeSmartRTL::init(bool ignore_checks)
2017-07-26 14:14:40 -03:00
{
if ((copter.position_ok() || ignore_checks) && g2.smart_rtl.is_active()) {
2017-07-26 14:14:40 -03:00
// initialise waypoint and spline controller
wp_nav->wp_and_spline_init();
// set current target to a reasonable stopping point
Vector3f stopping_point;
pos_control->get_stopping_point_xy(stopping_point);
pos_control->get_stopping_point_z(stopping_point);
wp_nav->set_wp_destination(stopping_point);
// initialise yaw to obey user parameter
copter.set_auto_yaw_mode(copter.get_default_auto_yaw_mode(true));
2017-07-26 14:14:40 -03:00
// wait for cleanup of return path
smart_rtl_state = SmartRTL_WaitForPathCleanup;
2017-07-26 14:14:40 -03:00
return true;
}
return false;
2017-07-26 14:14:40 -03:00
}
2017-09-08 23:45:31 -03:00
// perform cleanup required when leaving smart_rtl
void Copter::ModeSmartRTL::exit()
2017-07-26 14:14:40 -03:00
{
2017-09-08 23:45:31 -03:00
g2.smart_rtl.cancel_request_for_thorough_cleanup();
2017-07-26 14:14:40 -03:00
}
void Copter::ModeSmartRTL::run()
2017-07-26 14:14:40 -03:00
{
2017-09-08 23:45:31 -03:00
switch (smart_rtl_state) {
case SmartRTL_WaitForPathCleanup:
wait_cleanup_run();
2017-07-26 14:14:40 -03:00
break;
case SmartRTL_PathFollow:
path_follow_run();
2017-07-26 14:14:40 -03:00
break;
case SmartRTL_PreLandPosition:
pre_land_position_run();
2017-07-26 14:14:40 -03:00
break;
case SmartRTL_Descend:
descent_run(); // Re-using the descend method from normal rtl mode.
2017-07-26 14:14:40 -03:00
break;
case SmartRTL_Land:
land_run(true); // Re-using the land method from normal rtl mode.
2017-07-26 14:14:40 -03:00
break;
}
}
void Copter::ModeSmartRTL::wait_cleanup_run()
2017-07-26 14:14:40 -03:00
{
// hover at current target position
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
wp_nav->update_wpnav();
pos_control->update_z_controller();
attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_heading(),true);
2017-07-26 14:14:40 -03:00
// check if return path is computed and if yes, begin journey home
2017-09-08 23:45:31 -03:00
if (g2.smart_rtl.request_thorough_cleanup()) {
smart_rtl_state = SmartRTL_PathFollow;
2017-07-26 14:14:40 -03:00
}
}
void Copter::ModeSmartRTL::path_follow_run()
2017-07-26 14:14:40 -03:00
{
// if we are close to current target point, switch the next point to be our target.
if (wp_nav->reached_wp_destination()) {
Vector3f next_point;
2017-09-08 23:45:31 -03:00
if (g2.smart_rtl.pop_point(next_point)) {
bool fast_waypoint = true;
2017-09-08 23:45:31 -03:00
if (g2.smart_rtl.get_num_points() == 0) {
// this is the very last point, add 2m to the target alt and move to pre-land state
2017-07-26 14:14:40 -03:00
next_point.z -= 2.0f;
smart_rtl_state = SmartRTL_PreLandPosition;
fast_waypoint = false;
2017-07-26 14:14:40 -03:00
}
// send target to waypoint controller
wp_nav->set_wp_destination_NED(next_point);
wp_nav->set_fast_waypoint(fast_waypoint);
2017-07-26 14:14:40 -03:00
} else {
// this can only happen if we fail to get the semaphore which should never happen but just in case, land
smart_rtl_state = SmartRTL_PreLandPosition;
2017-07-26 14:14:40 -03:00
}
}
// update controllers
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
wp_nav->update_wpnav();
pos_control->update_z_controller();
// call attitude controller
if (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(), 0);
2017-07-26 14:14:40 -03:00
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_heading(),true);
2017-07-26 14:14:40 -03:00
}
}
void Copter::ModeSmartRTL::pre_land_position_run()
2017-07-26 14:14:40 -03:00
{
// if we are close to 2m above start point, we are ready to land.
if (wp_nav->reached_wp_destination()) {
// choose descend and hold, or land based on user parameter rtl_alt_final
if (g.rtl_alt_final <= 0 || copter.failsafe.radio) {
land_start();
smart_rtl_state = SmartRTL_Land;
2017-07-26 14:14:40 -03:00
} else {
set_descent_target_alt(copter.g.rtl_alt_final);
descent_start();
smart_rtl_state = SmartRTL_Descend;
2017-07-26 14:14:40 -03:00
}
}
// update controllers
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
wp_nav->update_wpnav();
pos_control->update_z_controller();
attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_heading(), true);
2017-07-26 14:14:40 -03:00
}
2017-09-08 23:45:31 -03:00
// save current position for use by the smart_rtl flight mode
void Copter::ModeSmartRTL::save_position()
2017-07-26 14:14:40 -03:00
{
const bool should_save_position = motors->armed() && (copter.control_mode != SMART_RTL);
2017-07-26 14:14:40 -03:00
copter.g2.smart_rtl.update(copter.position_ok(), should_save_position);
2017-07-26 14:14:40 -03:00
}
uint32_t Copter::ModeSmartRTL::wp_distance() const
{
return wp_nav->get_wp_distance_to_destination();
}
int32_t Copter::ModeSmartRTL::wp_bearing() const
{
return wp_nav->get_wp_bearing_to_destination();
}
#endif