#include "Sub.h"
#define GUIDED_POSVEL_TIMEOUT_MS 3000
#define GUIDED_ATTITUDE_TIMEOUT_MS 1000
static Vector3p posvel_pos_target_cm;
static Vector3f posvel_vel_target_cms;
static uint32_t update_time_ms;
struct {
uint32_t update_time_ms;
float roll_cd;
float pitch_cd;
float yaw_cd;
float climb_rate_cms;
} static guided_angle_state = {0,0.0f, 0.0f, 0.0f, 0.0f};
struct Guided_Limit {
uint32_t timeout_ms;
float alt_min_cm;
float alt_max_cm;
float horiz_max_cm;
uint32_t start_time_ms;
Vector3f start_pos_neu_cm;
} guided_limit;
bool ModeGuided::init(bool ignore_checks)
{
if (!sub.position_ok() && !ignore_checks) {
return false;
}
guided_pos_control_start();
return true;
}
autopilot_yaw_mode ModeGuided::get_default_auto_yaw_mode(bool rtl) const
{
switch (g.wp_yaw_behavior) {
case WP_YAW_BEHAVIOR_NONE:
return AUTO_YAW_HOLD;
break;
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL:
if (rtl) {
return AUTO_YAW_HOLD;
} else {
return AUTO_YAW_LOOK_AT_NEXT_WP;
}
break;
case WP_YAW_BEHAVIOR_LOOK_AHEAD:
return AUTO_YAW_LOOK_AHEAD;
break;
case WP_YAW_BEHAVIOR_CORRECT_XTRACK:
return AUTO_YAW_CORRECT_XTRACK;
break;
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP:
default:
return AUTO_YAW_LOOK_AT_NEXT_WP;
break;
}
}
void ModeGuided::guided_pos_control_start()
{
sub.guided_mode = Guided_WP;
sub.wp_nav.wp_and_spline_init_m();
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, false);
sub.yaw_rate_only = false;
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
}
void ModeGuided::guided_vel_control_start()
{
sub.guided_mode = Guided_Velocity;
position_control->D_set_max_speed_accel_cm(sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
position_control->D_set_correction_speed_accel_cm(sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
position_control->D_init_controller();
position_control->NE_init_controller();
sub.yaw_rate_only = false;
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
void ModeGuided::guided_posvel_control_start()
{
sub.guided_mode = Guided_PosVel;
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());
position_control->D_init_controller();
position_control->NE_init_controller();
sub.yaw_rate_only = false;
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
void ModeGuided::guided_angle_control_start()
{
sub.guided_mode = Guided_Angle;
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());
position_control->D_init_controller();
guided_angle_state.update_time_ms = AP_HAL::millis();
guided_angle_state.roll_cd = ahrs.roll_sensor;
guided_angle_state.pitch_cd = ahrs.pitch_sensor;
guided_angle_state.yaw_cd = ahrs.yaw_sensor;
guided_angle_state.climb_rate_cms = 0.0f;
sub.yaw_rate_only = false;
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
bool ModeGuided::guided_set_destination(const Vector3f& destination)
{
#if AP_FENCE_ENABLED
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
if (!sub.fence.check_destination_within_fence(dest_loc)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
return false;
}
#endif
if (sub.guided_mode != Guided_WP) {
guided_pos_control_start();
}
sub.wp_nav.set_wp_destination_NEU_cm(destination, false);
#if HAL_LOGGING_ENABLED
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f());
#endif
return true;
}
bool ModeGuided::guided_set_destination(const Location& dest_loc)
{
#if AP_FENCE_ENABLED
if (!sub.fence.check_destination_within_fence(dest_loc)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
return false;
}
#endif
if (sub.guided_mode != Guided_WP) {
guided_pos_control_start();
}
if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
return false;
}
#if HAL_LOGGING_ENABLED
sub.Log_Write_GuidedTarget(sub.guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f());
#endif
return true;
}
bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
{
#if AP_FENCE_ENABLED
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
if (!sub.fence.check_destination_within_fence(dest_loc)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
return false;
}
#endif
if (sub.guided_mode != Guided_WP) {
guided_pos_control_start();
}
guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
update_time_ms = AP_HAL::millis();
sub.wp_nav.set_wp_destination_NEU_cm(destination, false);
#if HAL_LOGGING_ENABLED
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f());
#endif
return true;
}
void ModeGuided::guided_set_velocity(const Vector3f& velocity)
{
if (sub.guided_mode != Guided_Velocity) {
guided_vel_control_start();
}
update_time_ms = AP_HAL::millis();
position_control->set_vel_desired_NEU_cms(velocity);
}
void ModeGuided::guided_set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
{
if (sub.guided_mode != Guided_Velocity) {
guided_vel_control_start();
}
guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
update_time_ms = AP_HAL::millis();
position_control->set_vel_desired_NEU_cms(velocity);
}
bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity)
{
#if AP_FENCE_ENABLED
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
if (!sub.fence.check_destination_within_fence(dest_loc)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
return false;
}
#endif
if (sub.guided_mode != Guided_PosVel) {
guided_posvel_control_start();
}
update_time_ms = AP_HAL::millis();
posvel_pos_target_cm = destination.topostype();
posvel_vel_target_cms = velocity;
position_control->input_pos_vel_accel_NE_cm(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());
float dz = posvel_pos_target_cm.z;
position_control->input_pos_vel_accel_U_cm(dz, posvel_vel_target_cms.z, 0);
posvel_pos_target_cm.z = dz;
#if HAL_LOGGING_ENABLED
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity);
#endif
return true;
}
bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
{
#if AP_FENCE_ENABLED
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
if (!sub.fence.check_destination_within_fence(dest_loc)) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
return false;
}
#endif
if (sub.guided_mode != Guided_PosVel) {
guided_posvel_control_start();
}
guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
update_time_ms = AP_HAL::millis();
posvel_pos_target_cm = destination.topostype();
posvel_vel_target_cms = velocity;
position_control->input_pos_vel_accel_NE_cm(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());
float dz = posvel_pos_target_cm.z;
position_control->input_pos_vel_accel_U_cm(dz, posvel_vel_target_cms.z, 0);
posvel_pos_target_cm.z = dz;
#if HAL_LOGGING_ENABLED
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity);
#endif
return true;
}
void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms)
{
if (sub.guided_mode != Guided_Angle) {
guided_angle_control_start();
}
q.to_euler(guided_angle_state.roll_cd, guided_angle_state.pitch_cd, guided_angle_state.yaw_cd);
guided_angle_state.roll_cd = degrees(guided_angle_state.roll_cd) * 100.0f;
guided_angle_state.pitch_cd = degrees(guided_angle_state.pitch_cd) * 100.0f;
guided_angle_state.yaw_cd = wrap_180_cd(degrees(guided_angle_state.yaw_cd) * 100.0f);
guided_angle_state.climb_rate_cms = climb_rate_cms;
guided_angle_state.update_time_ms = AP_HAL::millis();
}
void ModeGuided::guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
{
float current_yaw = wrap_2PI(AP::ahrs().get_yaw_rad());
float euler_yaw_angle;
float yaw_error;
euler_yaw_angle = wrap_2PI((yaw_cd * 0.01f));
yaw_error = wrap_PI(euler_yaw_angle - current_yaw);
int direction = 0;
if (yaw_error < 0){
direction = -1;
} else {
direction = 1;
}
if (use_yaw && !use_yaw_rate) {
sub.yaw_rate_only = false;
sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, 0.0f, direction, relative_angle);
} else if (use_yaw && use_yaw_rate) {
sub.yaw_rate_only = false;
sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, yaw_rate_cds * 0.01f, direction, relative_angle);
} else if (!use_yaw && use_yaw_rate) {
sub.yaw_rate_only = true;
sub.mode_auto.set_yaw_rate(yaw_rate_cds * 0.01f);
} else{
sub.yaw_rate_only = false;
set_auto_yaw_mode(AUTO_YAW_HOLD);
}
}
void ModeGuided::run()
{
switch (sub.guided_mode) {
case Guided_WP:
guided_pos_control_run();
break;
case Guided_Velocity:
guided_vel_control_run();
break;
case Guided_PosVel:
guided_posvel_control_run();
break;
case Guided_Angle:
guided_angle_control_run();
break;
}
}
void ModeGuided::guided_pos_control_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);
} else{
if (sub.yaw_rate_only){
set_auto_yaw_mode(AUTO_YAW_RATE);
} else{
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
}
}
}
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();
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
attitude_control->input_euler_angle_roll_pitch_slew_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);
} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
attitude_control->input_euler_angle_roll_pitch_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
}
}
void ModeGuided::guided_vel_control_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();
position_control->D_init_controller();
position_control->NE_init_controller();
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);
} else{
if (sub.yaw_rate_only){
set_auto_yaw_mode(AUTO_YAW_RATE);
} else{
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
}
}
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
uint32_t tnow = AP_HAL::millis();
if (tnow - update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !position_control->get_vel_desired_NEU_cms().is_zero()) {
position_control->set_vel_desired_NEU_cms(Vector3f(0,0,0));
}
position_control->NE_stop_pos_stabilisation();
position_control->NE_update_controller();
position_control->D_set_pos_target_from_climb_rate_cms(position_control->get_vel_desired_NEU_cms().z);
position_control->D_update_controller();
float lateral_out, forward_out;
sub.translate_pos_control_rp(lateral_out, forward_out);
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
attitude_control->input_euler_angle_roll_pitch_slew_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);
} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
attitude_control->input_euler_angle_roll_pitch_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
}
}
void ModeGuided::guided_posvel_control_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();
position_control->D_init_controller();
position_control->NE_init_controller();
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);
} else{
if (sub.yaw_rate_only){
set_auto_yaw_mode(AUTO_YAW_RATE);
} else{
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
}
}
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
uint32_t tnow = AP_HAL::millis();
if (tnow - update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !posvel_vel_target_cms.is_zero()) {
posvel_vel_target_cms.zero();
}
posvel_pos_target_cm += (posvel_vel_target_cms * position_control->get_dt_s()).topostype();
position_control->input_pos_vel_accel_NE_cm(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());
float pz = posvel_pos_target_cm.z;
position_control->input_pos_vel_accel_U_cm(pz, posvel_vel_target_cms.z, 0);
posvel_pos_target_cm.z = pz;
position_control->NE_update_controller();
position_control->D_update_controller();
float lateral_out, forward_out;
sub.translate_pos_control_rp(lateral_out, forward_out);
motors.set_lateral(lateral_out);
motors.set_forward(forward_out);
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
attitude_control->input_euler_angle_roll_pitch_slew_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);
} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
attitude_control->input_euler_angle_roll_pitch_yaw_cd(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
}
}
void ModeGuided::guided_angle_control_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();
position_control->D_init_controller();
return;
}
float roll_in = guided_angle_state.roll_cd;
float pitch_in = guided_angle_state.pitch_cd;
float total_in = norm(roll_in, pitch_in);
float angle_max = MIN(attitude_control->get_althold_lean_angle_max_cd(), attitude_control->lean_angle_max_cd());
if (total_in > angle_max) {
float ratio = angle_max / total_in;
roll_in *= ratio;
pitch_in *= ratio;
}
float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd);
float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -sub.wp_nav.get_default_speed_down_cms(), sub.wp_nav.get_default_speed_up_cms());
uint32_t tnow = AP_HAL::millis();
if (tnow - guided_angle_state.update_time_ms > GUIDED_ATTITUDE_TIMEOUT_MS) {
roll_in = 0.0f;
pitch_in = 0.0f;
climb_rate_cms = 0.0f;
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
attitude_control->input_euler_angle_roll_pitch_yaw_cd(roll_in, pitch_in, yaw_in, true);
position_control->D_set_pos_target_from_climb_rate_cms(climb_rate_cms);
position_control->D_update_controller();
}
void ModeGuided::guided_limit_clear()
{
guided_limit.timeout_ms = 0;
guided_limit.alt_min_cm = 0.0f;
guided_limit.alt_max_cm = 0.0f;
guided_limit.horiz_max_cm = 0.0f;
}
void ModeGuided::set_auto_yaw_mode(autopilot_yaw_mode yaw_mode)
{
if (sub.auto_yaw_mode == yaw_mode) {
return;
}
sub.auto_yaw_mode = yaw_mode;
switch (sub.auto_yaw_mode) {
case AUTO_YAW_HOLD:
break;
case AUTO_YAW_LOOK_AT_NEXT_WP:
break;
case AUTO_YAW_ROI:
sub.yaw_look_at_WP_bearing = ahrs.yaw_sensor;
break;
case AUTO_YAW_LOOK_AT_HEADING:
break;
case AUTO_YAW_LOOK_AHEAD:
sub.yaw_look_ahead_bearing = ahrs.yaw_sensor;
break;
case AUTO_YAW_RESETTOARMEDYAW:
break;
case AUTO_YAW_RATE:
break;
}
}
float ModeGuided::get_auto_heading()
{
switch (sub.auto_yaw_mode) {
case AUTO_YAW_ROI:
return sub.get_roi_yaw();
break;
case AUTO_YAW_LOOK_AT_HEADING:
return sub.yaw_look_at_heading;
break;
case AUTO_YAW_LOOK_AHEAD:
return sub.get_look_ahead_yaw();
break;
case AUTO_YAW_RESETTOARMEDYAW:
return sub.initial_armed_bearing;
break;
case AUTO_YAW_CORRECT_XTRACK: {
float track_bearing = get_bearing_cd(sub.wp_nav.get_wp_origin_NEU_cm().xy(), sub.wp_nav.get_wp_destination_NEU_cm().xy());
const Vector2f target_vel_ne_cms = position_control->get_vel_target_NEU_cms().xy();
float angle_error = 0.0f;
if (target_vel_ne_cms.length() >= position_control->NE_get_max_speed_cms() * 0.1f) {
const float desired_angle_cd = degrees(target_vel_ne_cms.angle()) * 100.0f;
angle_error = wrap_180_cd(desired_angle_cd - track_bearing);
}
float angle_limited = constrain_float(angle_error, -g.xtrack_angle_limit * 100.0f, g.xtrack_angle_limit * 100.0f);
return wrap_360_cd(track_bearing + angle_limited);
}
break;
case AUTO_YAW_LOOK_AT_NEXT_WP:
default:
return sub.wp_nav.get_yaw();
break;
}
}
void ModeGuided::guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm)
{
guided_limit.timeout_ms = timeout_ms;
guided_limit.alt_min_cm = alt_min_cm;
guided_limit.alt_max_cm = alt_max_cm;
guided_limit.horiz_max_cm = horiz_max_cm;
}
void ModeGuided::guided_limit_init_time_and_pos()
{
guided_limit.start_time_ms = AP_HAL::millis();
guided_limit.start_pos_neu_cm = inertial_nav.get_position_neu_cm();
}
bool ModeGuided::guided_limit_check()
{
if ((guided_limit.timeout_ms > 0) && (AP_HAL::millis() - guided_limit.start_time_ms >= guided_limit.timeout_ms)) {
return true;
}
const Vector3f& curr_pos_neu_cm = inertial_nav.get_position_neu_cm();
if (!is_zero(guided_limit.alt_min_cm) && (curr_pos_neu_cm.z < guided_limit.alt_min_cm)) {
return true;
}
if (!is_zero(guided_limit.alt_max_cm) && (curr_pos_neu_cm.z > guided_limit.alt_max_cm)) {
return true;
}
if (guided_limit.horiz_max_cm > 0.0f) {
const float horiz_move_cm = get_horizontal_distance(guided_limit.start_pos_neu_cm.xy(), curr_pos_neu_cm.xy());
if (horiz_move_cm > guided_limit.horiz_max_cm) {
return true;
}
}
return false;
}