#include "Sub.h"
bool ModeAuto::init(bool ignore_checks) {
if (!sub.position_ok() || !sub.mission.present()) {
return false;
}
sub.auto_mode = Auto_Loiter;
if (sub.auto_yaw_mode == AUTO_YAW_ROI) {
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
sub.wp_nav.wp_and_spline_init_m();
guided_limit_clear();
sub.mission.start_or_resume();
return true;
}
void ModeAuto::run()
{
sub.mission.update();
switch (sub.auto_mode) {
case Auto_WP:
case Auto_CircleMoveToEdge:
auto_wp_run();
break;
case Auto_Circle:
auto_circle_run();
break;
case Auto_NavGuided:
#if NAV_GUIDED
auto_nav_guided_run();
#endif
break;
case Auto_Loiter:
auto_loiter_run();
break;
case Auto_TerrainRecover:
auto_terrain_recover_run();
break;
}
}
void ModeAuto::auto_wp_start(const Vector3f& destination)
{
sub.auto_mode = Auto_WP;
sub.wp_nav.set_wp_destination_NEU_cm(destination, false);
if (sub.auto_yaw_mode != AUTO_YAW_ROI) {
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
}
}
void ModeAuto::auto_wp_start(const Location& dest_loc)
{
sub.auto_mode = Auto_WP;
if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Terrain data (rangefinder) not available");
sub.failsafe_terrain_on_event();
return;
}
if (sub.auto_yaw_mode != AUTO_YAW_ROI) {
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
}
}
void ModeAuto::auto_wp_run()
{
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.wp_nav.wp_and_spline_init_m();
return;
}
float target_yaw_rate = 0;
if (!sub.failsafe.pilot_input) {
target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) {
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
sub.failsafe_terrain_set_status(sub.wp_nav.update_wpnav());
float lateral_out, forward_out;
sub.translate_wpnav_rp(lateral_out, forward_out);
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
position_control->D_update_controller();
float target_roll, target_pitch;
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control->lean_angle_max_cd());
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_roll, target_pitch, target_yaw_rate);
} else {
attitude_control->input_euler_angle_roll_pitch_yaw_cd(target_roll, target_pitch, get_auto_heading(), true);
}
}
void ModeAuto::auto_circle_movetoedge_start(const Location &circle_center, float radius_m, bool ccw_turn)
{
sub.circle_nav.set_center(circle_center);
if (!is_zero(radius_m)) {
sub.circle_nav.set_radius_cm(radius_m * 100.0f);
}
float current_rate = sub.circle_nav.get_rate_degs();
current_rate = ccw_turn ? -fabsf(current_rate) : fabsf(current_rate);
sub.circle_nav.set_rate_degs(current_rate);
Vector3f circle_edge_neu_cm;
float dist_to_edge;
sub.circle_nav.get_closest_point_on_circle_NEU_cm(circle_edge_neu_cm, dist_to_edge);
if (dist_to_edge > 300.0f) {
sub.auto_mode = Auto_CircleMoveToEdge;
Location circle_edge(circle_edge_neu_cm, Location::AltFrame::ABOVE_ORIGIN);
circle_edge.copy_alt_from(circle_center);
if (!sub.wp_nav.set_wp_destination_loc(circle_edge)) {
sub.failsafe_terrain_on_event();
}
float dist_to_center = get_horizontal_distance(inertial_nav.get_position_xy_cm().topostype(), sub.circle_nav.get_center_NEU_cm().xy());
if (dist_to_center > sub.circle_nav.get_radius_cm() && dist_to_center > 500) {
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
} else {
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
} else {
auto_circle_start();
}
}
void ModeAuto::auto_circle_start()
{
sub.auto_mode = Auto_Circle;
sub.circle_nav.init_NEU_cm(sub.circle_nav.get_center_NEU_cm(), sub.circle_nav.center_is_terrain_alt(), sub.circle_nav.get_rate_degs());
}
void ModeAuto::auto_circle_run()
{
sub.failsafe_terrain_set_status(sub.circle_nav.update_cms());
float lateral_out, forward_out;
sub.translate_circle_nav_rp(lateral_out, forward_out);
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
position_control->D_update_controller();
attitude_control->input_euler_angle_roll_pitch_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), sub.circle_nav.get_yaw_cd(), true);
}
#if NAV_GUIDED
void ModeAuto::auto_nav_guided_start()
{
sub.mode_guided.init(true);
sub.auto_mode = Auto_NavGuided;
sub.mode_auto.guided_limit_init_time_and_pos();
}
void ModeAuto::auto_nav_guided_run()
{
sub.mode_guided.run();
}
#endif
bool ModeAuto::auto_loiter_start()
{
if (!sub.position_ok()) {
return false;
}
sub.auto_mode = Auto_Loiter;
Vector3f stopping_point_neu_cm;
sub.wp_nav.get_wp_stopping_point_NEU_cm(stopping_point_neu_cm);
sub.wp_nav.set_wp_destination_NEU_cm(stopping_point_neu_cm);
set_auto_yaw_mode(AUTO_YAW_HOLD);
return true;
}
void ModeAuto::auto_loiter_run()
{
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.wp_nav.wp_and_spline_init_m();
return;
}
float target_yaw_rate = 0;
if (!sub.failsafe.pilot_input) {
target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
sub.failsafe_terrain_set_status(sub.wp_nav.update_wpnav());
float lateral_out, forward_out;
sub.translate_wpnav_rp(lateral_out, forward_out);
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
position_control->D_update_controller();
float target_roll, target_pitch;
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control->lean_angle_max_cd());
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_roll, target_pitch, target_yaw_rate);
}
void ModeAuto::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle)
{
int32_t curr_yaw_target = attitude_control->get_att_target_euler_cd().z;
if (relative_angle == 0) {
sub.yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
} else {
if (direction < 0) {
angle_deg = -angle_deg;
}
sub.yaw_look_at_heading = wrap_360_cd((angle_deg * 100 + curr_yaw_target));
}
if (is_zero(turn_rate_dps)) {
sub.yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE;
} else {
sub.yaw_look_at_heading_slew = MIN(turn_rate_dps, AUTO_YAW_SLEW_RATE);
}
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
}
void ModeAuto::set_yaw_rate(float turn_rate_dps)
{
sub.yaw_look_at_heading_slew = MIN(turn_rate_dps, AUTO_YAW_SLEW_RATE);
set_auto_yaw_mode(AUTO_YAW_RATE);
}
void ModeAuto::set_auto_yaw_roi(const Location &roi_location)
{
if (!roi_location.initialised()) {
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
#if HAL_MOUNT_ENABLED
sub.camera_mount.clear_roi_target();
#endif
} else {
#if HAL_MOUNT_ENABLED
if (!sub.camera_mount.has_pan_control()) {
if (roi_location.get_vector_from_origin_NEU_cm(sub.roi_WP)) {
set_auto_yaw_mode(AUTO_YAW_ROI);
}
}
sub.camera_mount.set_roi_target(roi_location);
#else
if (roi_location.get_vector_from_origin_NEU_cm(sub.roi_WP)) {
set_auto_yaw_mode(AUTO_YAW_ROI);
}
#endif
}
}
bool ModeAuto::auto_terrain_recover_start()
{
#if AP_RANGEFINDER_ENABLED
switch (sub.rangefinder.status_orient(ROTATION_PITCH_270)) {
case RangeFinder::Status::OutOfRangeLow:
case RangeFinder::Status::OutOfRangeHigh:
case RangeFinder::Status::Good:
sub.auto_mode = Auto_TerrainRecover;
break;
default:
return false;
}
sub.fs_terrain_recover_start_ms = AP_HAL::millis();
sub.mission.stop();
sub.loiter_nav.clear_pilot_desired_acceleration();
sub.loiter_nav.init_target();
position_control->D_relax_controller(motors.get_throttle_hover());
position_control->D_set_max_speed_accel_cm(sub.wp_nav.get_default_speed_down_cms(), sub.wp_nav.get_default_speed_up_cms(), sub.wp_nav.get_accel_D_cmss());
position_control->D_set_correction_speed_accel_cm(sub.wp_nav.get_default_speed_down_cms(), sub.wp_nav.get_default_speed_up_cms(), sub.wp_nav.get_accel_D_cmss());
gcs().send_text(MAV_SEVERITY_WARNING, "Attempting auto failsafe recovery");
return true;
#else
return false;
#endif
}
void ModeAuto::auto_terrain_recover_run()
{
float target_climb_rate = 0;
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
sub.loiter_nav.init_target();
position_control->D_relax_controller(motors.get_throttle_hover());
return;
}
#if AP_RANGEFINDER_ENABLED
static uint32_t rangefinder_recovery_ms = 0;
switch (sub.rangefinder.status_orient(ROTATION_PITCH_270)) {
case RangeFinder::Status::OutOfRangeLow:
target_climb_rate = sub.wp_nav.get_default_speed_up_cms();
rangefinder_recovery_ms = 0;
break;
case RangeFinder::Status::OutOfRangeHigh:
target_climb_rate = sub.wp_nav.get_default_speed_down_cms();
rangefinder_recovery_ms = 0;
break;
case RangeFinder::Status::Good:
target_climb_rate = 0;
if (sub.rangefinder_state.alt_healthy) {
if (rangefinder_recovery_ms == 0) {
rangefinder_recovery_ms = AP_HAL::millis();
position_control->D_relax_controller(motors.get_throttle_hover());
}
if (AP_HAL::millis() > rangefinder_recovery_ms + 1500) {
gcs().send_text(MAV_SEVERITY_INFO, "Terrain failsafe recovery successful!");
sub.failsafe_terrain_set_status(true);
sub.failsafe.terrain = false;
sub.auto_mode = Auto_Loiter;
sub.mission.resume();
rangefinder_recovery_ms = 0;
}
}
break;
default:
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!");
sub.failsafe_terrain_act();
rangefinder_recovery_ms = 0;
return;
}
#else
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!");
sub.failsafe_terrain_act();
#endif
if (AP_HAL::millis() > sub.fs_terrain_recover_start_ms + FS_TERRAIN_RECOVER_TIMEOUT_MS) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery timeout!");
sub.failsafe_terrain_act();
}
sub.loiter_nav.update();
float lateral_out, forward_out;
sub.translate_wpnav_rp(lateral_out, forward_out);
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
position_control->D_set_pos_target_from_climb_rate_cms(target_climb_rate);
position_control->D_update_controller();
float target_roll = 0;
float target_pitch = 0;
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control->lean_angle_max_cd());
float target_yaw_rate = 0;
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_roll, target_pitch, target_yaw_rate);
}