Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/mode_guided.cpp
Views: 1798
#include "Sub.h"12/*3* Init and run calls for guided flight mode4*/56#define GUIDED_POSVEL_TIMEOUT_MS 3000 // guided mode's position-velocity controller times out after 3seconds with no new updates7#define GUIDED_ATTITUDE_TIMEOUT_MS 1000 // guided mode's attitude controller times out after 1 second with no new updates89static Vector3p posvel_pos_target_cm;10static Vector3f posvel_vel_target_cms;11static uint32_t update_time_ms;1213struct {14uint32_t update_time_ms;15float roll_cd;16float pitch_cd;17float yaw_cd;18float climb_rate_cms;19} static guided_angle_state = {0,0.0f, 0.0f, 0.0f, 0.0f};2021struct Guided_Limit {22uint32_t timeout_ms; // timeout (in seconds) from the time that guided is invoked23float alt_min_cm; // lower altitude limit in cm above home (0 = no limit)24float alt_max_cm; // upper altitude limit in cm above home (0 = no limit)25float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit)26uint32_t start_time;// system time in milliseconds that control was handed to the external computer27Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit28} guided_limit;2930// guided_init - initialise guided controller31bool ModeGuided::init(bool ignore_checks)32{33if (!sub.position_ok() && !ignore_checks) {34return false;35}3637// start in position control mode38guided_pos_control_start();39return true;40}4142// get_default_auto_yaw_mode - returns auto_yaw_mode based on WP_YAW_BEHAVIOR parameter43// set rtl parameter to true if this is during an RTL44autopilot_yaw_mode ModeGuided::get_default_auto_yaw_mode(bool rtl) const45{46switch (g.wp_yaw_behavior) {4748case WP_YAW_BEHAVIOR_NONE:49return AUTO_YAW_HOLD;50break;5152case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL:53if (rtl) {54return AUTO_YAW_HOLD;55} else {56return AUTO_YAW_LOOK_AT_NEXT_WP;57}58break;5960case WP_YAW_BEHAVIOR_LOOK_AHEAD:61return AUTO_YAW_LOOK_AHEAD;62break;6364case WP_YAW_BEHAVIOR_CORRECT_XTRACK:65return AUTO_YAW_CORRECT_XTRACK;66break;6768case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP:69default:70return AUTO_YAW_LOOK_AT_NEXT_WP;71break;72}73}747576// initialise guided mode's position controller77void ModeGuided::guided_pos_control_start()78{79// set to position control mode80sub.guided_mode = Guided_WP;8182// initialise waypoint controller83sub.wp_nav.wp_and_spline_init();8485// initialise wpnav to stopping point at current altitude86// To-Do: set to current location if disarmed?87// To-Do: set to stopping point altitude?88Vector3f stopping_point;89sub.wp_nav.get_wp_stopping_point(stopping_point);9091// no need to check return status because terrain data is not used92sub.wp_nav.set_wp_destination(stopping_point, false);9394// initialise yaw95sub.yaw_rate_only = false;96set_auto_yaw_mode(get_default_auto_yaw_mode(false));97}9899// initialise guided mode's velocity controller100void ModeGuided::guided_vel_control_start()101{102// set guided_mode to velocity controller103sub.guided_mode = Guided_Velocity;104105// initialize vertical maximum speeds and acceleration106position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);107position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);108109// initialise velocity controller110position_control->init_z_controller();111position_control->init_xy_controller();112113// pilot always controls yaw114sub.yaw_rate_only = false;115set_auto_yaw_mode(AUTO_YAW_HOLD);116}117118// initialise guided mode's posvel controller119void ModeGuided::guided_posvel_control_start()120{121// set guided_mode to velocity controller122sub.guided_mode = Guided_PosVel;123124// set vertical speed and acceleration125position_control->set_max_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());126position_control->set_correction_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());127128// initialise velocity controller129position_control->init_z_controller();130position_control->init_xy_controller();131132// pilot always controls yaw133sub.yaw_rate_only = false;134set_auto_yaw_mode(AUTO_YAW_HOLD);135}136137// initialise guided mode's angle controller138void ModeGuided::guided_angle_control_start()139{140// set guided_mode to velocity controller141sub.guided_mode = Guided_Angle;142143// set vertical speed and acceleration144position_control->set_max_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());145position_control->set_correction_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());146147// initialise velocity controller148position_control->init_z_controller();149150// initialise targets151guided_angle_state.update_time_ms = AP_HAL::millis();152guided_angle_state.roll_cd = ahrs.roll_sensor;153guided_angle_state.pitch_cd = ahrs.pitch_sensor;154guided_angle_state.yaw_cd = ahrs.yaw_sensor;155guided_angle_state.climb_rate_cms = 0.0f;156157// pilot always controls yaw158sub.yaw_rate_only = false;159set_auto_yaw_mode(AUTO_YAW_HOLD);160}161162// guided_set_destination - sets guided mode's target destination163// Returns true if the fence is enabled and guided waypoint is within the fence164// else return false if the waypoint is outside the fence165bool ModeGuided::guided_set_destination(const Vector3f& destination)166{167#if AP_FENCE_ENABLED168// reject destination if outside the fence169const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);170if (!sub.fence.check_destination_within_fence(dest_loc)) {171LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);172// failure is propagated to GCS with NAK173return false;174}175#endif176177// ensure we are in position control mode178if (sub.guided_mode != Guided_WP) {179guided_pos_control_start();180}181182// no need to check return status because terrain data is not used183sub.wp_nav.set_wp_destination(destination, false);184185#if HAL_LOGGING_ENABLED186// log target187sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f());188#endif189190return true;191}192193// sets guided mode's target from a Location object194// returns false if destination could not be set (probably caused by missing terrain data)195// or if the fence is enabled and guided waypoint is outside the fence196bool ModeGuided::guided_set_destination(const Location& dest_loc)197{198#if AP_FENCE_ENABLED199// reject destination outside the fence.200// Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails201if (!sub.fence.check_destination_within_fence(dest_loc)) {202LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);203// failure is propagated to GCS with NAK204return false;205}206#endif207208// ensure we are in position control mode209if (sub.guided_mode != Guided_WP) {210guided_pos_control_start();211}212213if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) {214// failure to set destination can only be because of missing terrain data215LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);216// failure is propagated to GCS with NAK217return false;218}219220#if HAL_LOGGING_ENABLED221// log target222sub.Log_Write_GuidedTarget(sub.guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f());223#endif224225return true;226}227228// guided_set_destination - sets guided mode's target destination and target heading229// Returns true if the fence is enabled and guided waypoint is within the fence230// else return false if the waypoint is outside the fence231bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)232{233#if AP_FENCE_ENABLED234// reject destination if outside the fence235const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);236if (!sub.fence.check_destination_within_fence(dest_loc)) {237LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);238// failure is propagated to GCS with NAK239return false;240}241#endif242243// ensure we are in position control mode244if (sub.guided_mode != Guided_WP) {245guided_pos_control_start();246}247248// set yaw state249guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);250251update_time_ms = AP_HAL::millis();252253// no need to check return status because terrain data is not used254sub.wp_nav.set_wp_destination(destination, false);255256#if HAL_LOGGING_ENABLED257// log target258sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f());259#endif260261return true;262}263264// guided_set_velocity - sets guided mode's target velocity265void ModeGuided::guided_set_velocity(const Vector3f& velocity)266{267// check we are in velocity control mode268if (sub.guided_mode != Guided_Velocity) {269guided_vel_control_start();270}271272update_time_ms = AP_HAL::millis();273274// set position controller velocity target275position_control->set_vel_desired_cms(velocity);276}277278// guided_set_velocity - sets guided mode's target velocity279void ModeGuided::guided_set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)280{281// check we are in velocity control mode282if (sub.guided_mode != Guided_Velocity) {283guided_vel_control_start();284}285286// set yaw state287guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);288289update_time_ms = AP_HAL::millis();290291// set position controller velocity target292position_control->set_vel_desired_cms(velocity);293294}295296// set guided mode posvel target297bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity)298{299#if AP_FENCE_ENABLED300// reject destination if outside the fence301const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);302if (!sub.fence.check_destination_within_fence(dest_loc)) {303LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);304// failure is propagated to GCS with NAK305return false;306}307#endif308309// check we are in posvel control mode310if (sub.guided_mode != Guided_PosVel) {311guided_posvel_control_start();312}313314update_time_ms = AP_HAL::millis();315posvel_pos_target_cm = destination.topostype();316posvel_vel_target_cms = velocity;317318position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());319float dz = posvel_pos_target_cm.z;320position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0);321posvel_pos_target_cm.z = dz;322323#if HAL_LOGGING_ENABLED324// log target325sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity);326#endif327328return true;329}330331// set guided mode posvel target332bool 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)333{334#if AP_FENCE_ENABLED335// reject destination if outside the fence336const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);337if (!sub.fence.check_destination_within_fence(dest_loc)) {338LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);339// failure is propagated to GCS with NAK340return false;341}342#endif343344// check we are in posvel control mode345if (sub.guided_mode != Guided_PosVel) {346guided_posvel_control_start();347}348349// set yaw state350guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);351352update_time_ms = AP_HAL::millis();353354posvel_pos_target_cm = destination.topostype();355posvel_vel_target_cms = velocity;356357position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());358float dz = posvel_pos_target_cm.z;359position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0);360posvel_pos_target_cm.z = dz;361362#if HAL_LOGGING_ENABLED363// log target364sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity);365#endif366367return true;368}369370// set guided mode angle target371void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms)372{373// check we are in angle control mode374if (sub.guided_mode != Guided_Angle) {375guided_angle_control_start();376}377378// convert quaternion to euler angles379q.to_euler(guided_angle_state.roll_cd, guided_angle_state.pitch_cd, guided_angle_state.yaw_cd);380guided_angle_state.roll_cd = ToDeg(guided_angle_state.roll_cd) * 100.0f;381guided_angle_state.pitch_cd = ToDeg(guided_angle_state.pitch_cd) * 100.0f;382guided_angle_state.yaw_cd = wrap_180_cd(ToDeg(guided_angle_state.yaw_cd) * 100.0f);383384guided_angle_state.climb_rate_cms = climb_rate_cms;385guided_angle_state.update_time_ms = AP_HAL::millis();386}387388// helper function to set yaw state and targets389void ModeGuided::guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)390{391float current_yaw = wrap_2PI(AP::ahrs().get_yaw());392float euler_yaw_angle;393float yaw_error;394395euler_yaw_angle = wrap_2PI((yaw_cd * 0.01f));396yaw_error = wrap_PI(euler_yaw_angle - current_yaw);397398int direction = 0;399if (yaw_error < 0){400direction = -1;401} else {402direction = 1;403}404405/*406case 1: target yaw only407case 2: target yaw and yaw rate408case 3: target yaw rate only409case 4: hold current yaw410*/411if (use_yaw && !use_yaw_rate) {412sub.yaw_rate_only = false;413sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, 0.0f, direction, relative_angle);414} else if (use_yaw && use_yaw_rate) {415sub.yaw_rate_only = false;416sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, yaw_rate_cds * 0.01f, direction, relative_angle);417} else if (!use_yaw && use_yaw_rate) {418sub.yaw_rate_only = true;419sub.mode_auto.set_yaw_rate(yaw_rate_cds * 0.01f);420} else{421sub.yaw_rate_only = false;422set_auto_yaw_mode(AUTO_YAW_HOLD);423}424}425426// guided_run - runs the guided controller427// should be called at 100hz or more428void ModeGuided::run()429{430// call the correct auto controller431switch (sub.guided_mode) {432433case Guided_WP:434// run position controller435guided_pos_control_run();436break;437438case Guided_Velocity:439// run velocity controller440guided_vel_control_run();441break;442443case Guided_PosVel:444// run position-velocity controller445guided_posvel_control_run();446break;447448case Guided_Angle:449// run angle controller450guided_angle_control_run();451break;452}453}454455// guided_pos_control_run - runs the guided position controller456// called from guided_run457void ModeGuided::guided_pos_control_run()458{459// if motors not enabled set throttle to zero and exit immediately460if (!motors.armed()) {461motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);462// Sub vehicles do not stabilize roll/pitch/yaw when disarmed463attitude_control->set_throttle_out(0,true,g.throttle_filt);464attitude_control->relax_attitude_controllers();465sub.wp_nav.wp_and_spline_init();466return;467}468469// process pilot's yaw input470float target_yaw_rate = 0;471if (!sub.failsafe.pilot_input) {472// get pilot's desired yaw rate473target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());474if (!is_zero(target_yaw_rate)) {475set_auto_yaw_mode(AUTO_YAW_HOLD);476} else{477if (sub.yaw_rate_only){478set_auto_yaw_mode(AUTO_YAW_RATE);479} else{480set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);481}482}483}484485// set motors to full range486motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);487488// run waypoint controller489sub.failsafe_terrain_set_status(sub.wp_nav.update_wpnav());490491float lateral_out, forward_out;492sub.translate_wpnav_rp(lateral_out, forward_out);493494// Send to forward/lateral outputs495motors.set_lateral(lateral_out);496motors.set_forward(forward_out);497498// WP_Nav has set the vertical position control targets499// run the vertical position controller and set output throttle500position_control->update_z_controller();501502// call attitude controller503if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {504// roll & pitch & yaw rate from pilot505attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);506} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {507// roll, pitch from pilot, yaw & yaw_rate from auto_control508target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;509attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);510} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {511// roll, pitch from pilot, yaw_rate from auto_control512target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;513attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);514} else {515// roll, pitch from pilot, yaw heading from auto_heading()516attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);517}518}519520// guided_vel_control_run - runs the guided velocity controller521// called from guided_run522void ModeGuided::guided_vel_control_run()523{524// ifmotors not enabled set throttle to zero and exit immediately525if (!motors.armed()) {526motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);527// Sub vehicles do not stabilize roll/pitch/yaw when disarmed528attitude_control->set_throttle_out(0,true,g.throttle_filt);529attitude_control->relax_attitude_controllers();530// initialise velocity controller531position_control->init_z_controller();532position_control->init_xy_controller();533return;534}535536// process pilot's yaw input537float target_yaw_rate = 0;538if (!sub.failsafe.pilot_input) {539// get pilot's desired yaw rate540target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());541if (!is_zero(target_yaw_rate)) {542set_auto_yaw_mode(AUTO_YAW_HOLD);543} else{544if (sub.yaw_rate_only){545set_auto_yaw_mode(AUTO_YAW_RATE);546} else{547set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);548}549}550}551552// set motors to full range553motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);554555// set velocity to zero if no updates received for 3 seconds556uint32_t tnow = AP_HAL::millis();557if (tnow - update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !position_control->get_vel_desired_cms().is_zero()) {558position_control->set_vel_desired_cms(Vector3f(0,0,0));559}560561position_control->stop_pos_xy_stabilisation();562// call velocity controller which includes z axis controller563position_control->update_xy_controller();564565position_control->set_pos_target_z_from_climb_rate_cm(position_control->get_vel_desired_cms().z);566position_control->update_z_controller();567568float lateral_out, forward_out;569sub.translate_pos_control_rp(lateral_out, forward_out);570571// Send to forward/lateral outputs572motors.set_lateral(lateral_out);573motors.set_forward(forward_out);574575// call attitude controller576if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {577// roll & pitch & yaw rate from pilot578attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);579} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {580// roll, pitch from pilot, yaw & yaw_rate from auto_control581target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;582attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);583} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {584// roll, pitch from pilot, yaw_rate from auto_control585target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;586attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);587} else {588// roll, pitch from pilot, yaw heading from auto_heading()589attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);590}591}592593// guided_posvel_control_run - runs the guided posvel controller594// called from guided_run595void ModeGuided::guided_posvel_control_run()596{597// if motors not enabled set throttle to zero and exit immediately598if (!motors.armed()) {599motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);600// Sub vehicles do not stabilize roll/pitch/yaw when disarmed601attitude_control->set_throttle_out(0,true,g.throttle_filt);602attitude_control->relax_attitude_controllers();603// initialise velocity controller604position_control->init_z_controller();605position_control->init_xy_controller();606return;607}608609// process pilot's yaw input610float target_yaw_rate = 0;611612if (!sub.failsafe.pilot_input) {613// get pilot's desired yaw rate614target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());615if (!is_zero(target_yaw_rate)) {616set_auto_yaw_mode(AUTO_YAW_HOLD);617} else{618if (sub.yaw_rate_only){619set_auto_yaw_mode(AUTO_YAW_RATE);620} else{621set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);622}623}624}625626// set motors to full range627motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);628629// set velocity to zero if no updates received for 3 seconds630uint32_t tnow = AP_HAL::millis();631if (tnow - update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !posvel_vel_target_cms.is_zero()) {632posvel_vel_target_cms.zero();633}634635// advance position target using velocity target636posvel_pos_target_cm += (posvel_vel_target_cms * position_control->get_dt()).topostype();637638// send position and velocity targets to position controller639position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());640float pz = posvel_pos_target_cm.z;641position_control->input_pos_vel_accel_z(pz, posvel_vel_target_cms.z, 0);642posvel_pos_target_cm.z = pz;643644// run position controller645position_control->update_xy_controller();646position_control->update_z_controller();647648float lateral_out, forward_out;649sub.translate_pos_control_rp(lateral_out, forward_out);650651// Send to forward/lateral outputs652motors.set_lateral(lateral_out);653motors.set_forward(forward_out);654655// call attitude controller656if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {657// roll & pitch & yaw rate from pilot658attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);659} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {660// roll, pitch from pilot, yaw & yaw_rate from auto_control661target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;662attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);663} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {664// roll, pitch from pilot, and yaw_rate from auto_control665target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;666attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);667} else {668// roll, pitch from pilot, yaw heading from auto_heading()669attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);670}671}672673// guided_angle_control_run - runs the guided angle controller674// called from guided_run675void ModeGuided::guided_angle_control_run()676{677// if motors not enabled set throttle to zero and exit immediately678if (!motors.armed()) {679motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);680// Sub vehicles do not stabilize roll/pitch/yaw when disarmed681attitude_control->set_throttle_out(0.0f,true,g.throttle_filt);682attitude_control->relax_attitude_controllers();683// initialise velocity controller684position_control->init_z_controller();685return;686}687688// constrain desired lean angles689float roll_in = guided_angle_state.roll_cd;690float pitch_in = guided_angle_state.pitch_cd;691float total_in = norm(roll_in, pitch_in);692float angle_max = MIN(attitude_control->get_althold_lean_angle_max_cd(), sub.aparm.angle_max);693if (total_in > angle_max) {694float ratio = angle_max / total_in;695roll_in *= ratio;696pitch_in *= ratio;697}698699// wrap yaw request700float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd);701702// constrain climb rate703float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up());704705// check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds706uint32_t tnow = AP_HAL::millis();707if (tnow - guided_angle_state.update_time_ms > GUIDED_ATTITUDE_TIMEOUT_MS) {708roll_in = 0.0f;709pitch_in = 0.0f;710climb_rate_cms = 0.0f;711}712713// set motors to full range714motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);715716// call attitude controller717attitude_control->input_euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true);718719// call position controller720position_control->set_pos_target_z_from_climb_rate_cm(climb_rate_cms);721position_control->update_z_controller();722}723724// Guided Limit code725726// guided_limit_clear - clear/turn off guided limits727void ModeGuided::guided_limit_clear()728{729guided_limit.timeout_ms = 0;730guided_limit.alt_min_cm = 0.0f;731guided_limit.alt_max_cm = 0.0f;732guided_limit.horiz_max_cm = 0.0f;733}734735736// set_auto_yaw_mode - sets the yaw mode for auto737void ModeGuided::set_auto_yaw_mode(autopilot_yaw_mode yaw_mode)738{739// return immediately if no change740if (sub.auto_yaw_mode == yaw_mode) {741return;742}743sub.auto_yaw_mode = yaw_mode;744745// perform initialisation746switch (sub.auto_yaw_mode) {747748case AUTO_YAW_HOLD:749// pilot controls the heading750break;751752case AUTO_YAW_LOOK_AT_NEXT_WP:753// wpnav will initialise heading when wpnav's set_destination method is called754break;755756case AUTO_YAW_ROI:757// point towards a location held in yaw_look_at_WP758sub.yaw_look_at_WP_bearing = ahrs.yaw_sensor;759break;760761case AUTO_YAW_LOOK_AT_HEADING:762// keep heading pointing in the direction held in yaw_look_at_heading763// caller should set the yaw_look_at_heading764break;765766case AUTO_YAW_LOOK_AHEAD:767// Commanded Yaw to automatically look ahead.768sub.yaw_look_ahead_bearing = ahrs.yaw_sensor;769break;770771case AUTO_YAW_RESETTOARMEDYAW:772// initial_armed_bearing will be set during arming so no init required773break;774775case AUTO_YAW_RATE:776// set target yaw rate to yaw_look_at_heading_slew777break;778}779}780781// get_auto_heading - returns target heading depending upon auto_yaw_mode782// 100hz update rate783float ModeGuided::get_auto_heading()784{785switch (sub.auto_yaw_mode) {786787case AUTO_YAW_ROI:788// point towards a location held in roi_WP789return sub.get_roi_yaw();790break;791792case AUTO_YAW_LOOK_AT_HEADING:793// keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed794return sub.yaw_look_at_heading;795break;796797case AUTO_YAW_LOOK_AHEAD:798// Commanded Yaw to automatically look ahead.799return sub.get_look_ahead_yaw();800break;801802case AUTO_YAW_RESETTOARMEDYAW:803// changes yaw to be same as when quad was armed804return sub.initial_armed_bearing;805break;806807case AUTO_YAW_CORRECT_XTRACK: {808// TODO return current yaw if not in appropriate mode809// Bearing of current track (centidegrees)810float track_bearing = get_bearing_cd(sub.wp_nav.get_wp_origin().xy(), sub.wp_nav.get_wp_destination().xy());811812// Bearing from current position towards intermediate position target (centidegrees)813const Vector2f target_vel_xy = position_control->get_vel_target_cms().xy();814float angle_error = 0.0f;815if (target_vel_xy.length() >= position_control->get_max_speed_xy_cms() * 0.1f) {816const float desired_angle_cd = degrees(target_vel_xy.angle()) * 100.0f;817angle_error = wrap_180_cd(desired_angle_cd - track_bearing);818}819float angle_limited = constrain_float(angle_error, -g.xtrack_angle_limit * 100.0f, g.xtrack_angle_limit * 100.0f);820return wrap_360_cd(track_bearing + angle_limited);821}822break;823824case AUTO_YAW_LOOK_AT_NEXT_WP:825default:826// point towards next waypoint.827// we don't use wp_bearing because we don't want the vehicle to turn too much during flight828return sub.wp_nav.get_yaw();829break;830}831}832// guided_limit_set - set guided timeout and movement limits833void ModeGuided::guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm)834{835guided_limit.timeout_ms = timeout_ms;836guided_limit.alt_min_cm = alt_min_cm;837guided_limit.alt_max_cm = alt_max_cm;838guided_limit.horiz_max_cm = horiz_max_cm;839}840841// guided_limit_init_time_and_pos - initialise guided start time and position as reference for limit checking842// only called from AUTO mode's auto_nav_guided_start function843void ModeGuided::guided_limit_init_time_and_pos()844{845// initialise start time846guided_limit.start_time = AP_HAL::millis();847848// initialise start position from current position849guided_limit.start_pos = inertial_nav.get_position_neu_cm();850}851852// guided_limit_check - returns true if guided mode has breached a limit853// used when guided is invoked from the NAV_GUIDED_ENABLE mission command854bool ModeGuided::guided_limit_check()855{856// check if we have passed the timeout857if ((guided_limit.timeout_ms > 0) && (AP_HAL::millis() - guided_limit.start_time >= guided_limit.timeout_ms)) {858return true;859}860861// get current location862const Vector3f& curr_pos = inertial_nav.get_position_neu_cm();863864// check if we have gone below min alt865if (!is_zero(guided_limit.alt_min_cm) && (curr_pos.z < guided_limit.alt_min_cm)) {866return true;867}868869// check if we have gone above max alt870if (!is_zero(guided_limit.alt_max_cm) && (curr_pos.z > guided_limit.alt_max_cm)) {871return true;872}873874// check if we have gone beyond horizontal limit875if (guided_limit.horiz_max_cm > 0.0f) {876const float horiz_move = get_horizontal_distance_cm(guided_limit.start_pos.xy(), curr_pos.xy());877if (horiz_move > guided_limit.horiz_max_cm) {878return true;879}880}881882// if we got this far we must be within limits883return false;884}885886887