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_auto.cpp
Views: 1798
#include "Sub.h"12/*3* control_auto.cpp4* Contains the mission, waypoint navigation and NAV_CMD item implementation5*6* While in the auto flight mode, navigation or do/now commands can be run.7* Code in this file implements the navigation commands8*/9bool ModeAuto::init(bool ignore_checks) {10if (!sub.position_ok() || sub.mission.num_commands() < 2) {11return false;12}1314sub.auto_mode = Auto_Loiter;1516// stop ROI from carrying over from previous runs of the mission17// To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check18if (sub.auto_yaw_mode == AUTO_YAW_ROI) {19set_auto_yaw_mode(AUTO_YAW_HOLD);20}2122// initialise waypoint controller23sub.wp_nav.wp_and_spline_init();2425// clear guided limits26guided_limit_clear();2728// start/resume the mission (based on MIS_RESTART parameter)29sub.mission.start_or_resume();30return true;31}3233// auto_run - runs the appropriate auto controller34// according to the current auto_mode35void ModeAuto::run()36{37sub.mission.update();3839// call the correct auto controller40switch (sub.auto_mode) {4142case Auto_WP:43case Auto_CircleMoveToEdge:44auto_wp_run();45break;4647case Auto_Circle:48auto_circle_run();49break;5051case Auto_NavGuided:52#if NAV_GUIDED53auto_nav_guided_run();54#endif55break;5657case Auto_Loiter:58auto_loiter_run();59break;6061case Auto_TerrainRecover:62auto_terrain_recover_run();63break;64}65}6667// auto_wp_start - initialises waypoint controller to implement flying to a particular destination68void ModeAuto::auto_wp_start(const Vector3f& destination)69{70sub.auto_mode = Auto_WP;7172// initialise wpnav (no need to check return status because terrain data is not used)73sub.wp_nav.set_wp_destination(destination, false);7475// initialise yaw76// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI77if (sub.auto_yaw_mode != AUTO_YAW_ROI) {78set_auto_yaw_mode(get_default_auto_yaw_mode(false));79}80}8182// auto_wp_start - initialises waypoint controller to implement flying to a particular destination83void ModeAuto::auto_wp_start(const Location& dest_loc)84{85sub.auto_mode = Auto_WP;8687// send target to waypoint controller88if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) {89// failure to set destination can only be because of missing terrain data90gcs().send_text(MAV_SEVERITY_WARNING, "Terrain data (rangefinder) not available");91sub.failsafe_terrain_on_event();92return;93}9495// initialise yaw96// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI97if (sub.auto_yaw_mode != AUTO_YAW_ROI) {98set_auto_yaw_mode(get_default_auto_yaw_mode(false));99}100}101102// auto_wp_run - runs the auto waypoint controller103// called by auto_run at 100hz or more104void ModeAuto::auto_wp_run()105{106// if not armed set throttle to zero and exit immediately107if (!motors.armed()) {108// To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off109// (of course it would be better if people just used take-off)110// call attitude controller111// Sub vehicles do not stabilize roll/pitch/yaw when disarmed112motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);113attitude_control->set_throttle_out(0,true,g.throttle_filt);114attitude_control->relax_attitude_controllers();115sub.wp_nav.wp_and_spline_init(); // Reset xy target116return;117}118119// process pilot's yaw input120float target_yaw_rate = 0;121if (!sub.failsafe.pilot_input) {122// get pilot's desired yaw rate123target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());124if (!is_zero(target_yaw_rate)) {125set_auto_yaw_mode(AUTO_YAW_HOLD);126}127}128129// set motors to full range130motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);131132// run waypoint controller133// TODO logic for terrain tracking target going below fence limit134// TODO implement waypoint radius individually for each waypoint based on cmd.p2135// TODO fix auto yaw heading to switch to something appropriate when mission complete and switches to loiter136sub.failsafe_terrain_set_status(sub.wp_nav.update_wpnav());137138///////////////////////139// update xy outputs //140141float lateral_out, forward_out;142sub.translate_wpnav_rp(lateral_out, forward_out);143144// Send to forward/lateral outputs145motors.set_lateral(lateral_out);146motors.set_forward(forward_out);147148// WP_Nav has set the vertical position control targets149// run the vertical position controller and set output throttle150position_control->update_z_controller();151152////////////////////////////153// update attitude output //154155// get pilot desired lean angles156float target_roll, target_pitch;157sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);158159// call attitude controller160if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {161// roll & pitch & yaw rate from pilot162attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);163} else {164// roll, pitch from pilot, yaw heading from auto_heading()165attitude_control->input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true);166}167}168169// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location170// we assume the caller has set the circle's circle with sub.circle_nav.set_center()171// we assume the caller has performed all required GPS_ok checks172void ModeAuto::auto_circle_movetoedge_start(const Location &circle_center, float radius_m, bool ccw_turn)173{174// set circle center175sub.circle_nav.set_center(circle_center);176177// set circle radius178if (!is_zero(radius_m)) {179sub.circle_nav.set_radius_cm(radius_m * 100.0f);180}181182// set circle direction by using rate183float current_rate = sub.circle_nav.get_rate();184current_rate = ccw_turn ? -fabsf(current_rate) : fabsf(current_rate);185sub.circle_nav.set_rate(current_rate);186187// check our distance from edge of circle188Vector3f circle_edge_neu;189float dist_to_edge;190sub.circle_nav.get_closest_point_on_circle(circle_edge_neu, dist_to_edge);191192// if more than 3m then fly to edge193if (dist_to_edge > 300.0f) {194// set the state to move to the edge of the circle195sub.auto_mode = Auto_CircleMoveToEdge;196197// convert circle_edge_neu to Location198Location circle_edge(circle_edge_neu, Location::AltFrame::ABOVE_ORIGIN);199200// convert altitude to same as command201circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());202203// initialise wpnav to move to edge of circle204if (!sub.wp_nav.set_wp_destination_loc(circle_edge)) {205// failure to set destination can only be because of missing terrain data206sub.failsafe_terrain_on_event();207}208209// if we are outside the circle, point at the edge, otherwise hold yaw210float dist_to_center = get_horizontal_distance_cm(inertial_nav.get_position_xy_cm().topostype(), sub.circle_nav.get_center().xy());211if (dist_to_center > sub.circle_nav.get_radius() && dist_to_center > 500) {212set_auto_yaw_mode(get_default_auto_yaw_mode(false));213} else {214// vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle215set_auto_yaw_mode(AUTO_YAW_HOLD);216}217} else {218auto_circle_start();219}220}221222// auto_circle_start - initialises controller to fly a circle in AUTO flight mode223// assumes that circle_nav object has already been initialised with circle center and radius224void ModeAuto::auto_circle_start()225{226sub.auto_mode = Auto_Circle;227228// initialise circle controller229sub.circle_nav.init(sub.circle_nav.get_center(), sub.circle_nav.center_is_terrain_alt(), sub.circle_nav.get_rate());230}231232// auto_circle_run - circle in AUTO flight mode233// called by auto_run at 100hz or more234void ModeAuto::auto_circle_run()235{236// call circle controller237sub.failsafe_terrain_set_status(sub.circle_nav.update());238239float lateral_out, forward_out;240sub.translate_circle_nav_rp(lateral_out, forward_out);241242// Send to forward/lateral outputs243motors.set_lateral(lateral_out);244motors.set_forward(forward_out);245246// WP_Nav has set the vertical position control targets247// run the vertical position controller and set output throttle248position_control->update_z_controller();249250// roll & pitch from waypoint controller, yaw rate from pilot251attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), sub.circle_nav.get_yaw(), true);252}253254#if NAV_GUIDED255// auto_nav_guided_start - hand over control to external navigation controller in AUTO mode256void ModeAuto::auto_nav_guided_start()257{258sub.mode_guided.init(true);259sub.auto_mode = Auto_NavGuided;260// initialise guided start time and position as reference for limit checking261sub.mode_auto.guided_limit_init_time_and_pos();262}263264// auto_nav_guided_run - allows control by external navigation controller265// called by auto_run at 100hz or more266void ModeAuto::auto_nav_guided_run()267{268// call regular guided flight mode run function269sub.mode_guided.run();270}271#endif // NAV_GUIDED272273// auto_loiter_start - initialises loitering in auto mode274// returns success/failure because this can be called by exit_mission275bool ModeAuto::auto_loiter_start()276{277// return failure if GPS is bad278if (!sub.position_ok()) {279return false;280}281sub.auto_mode = Auto_Loiter;282283// calculate stopping point284Vector3f stopping_point;285sub.wp_nav.get_wp_stopping_point(stopping_point);286287// initialise waypoint controller target to stopping point288sub.wp_nav.set_wp_destination(stopping_point);289290// hold yaw at current heading291set_auto_yaw_mode(AUTO_YAW_HOLD);292293return true;294}295296// auto_loiter_run - loiter in AUTO flight mode297// called by auto_run at 100hz or more298void ModeAuto::auto_loiter_run()299{300// if not armed set throttle to zero and exit immediately301if (!motors.armed()) {302motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);303// Sub vehicles do not stabilize roll/pitch/yaw when disarmed304attitude_control->set_throttle_out(0,true,g.throttle_filt);305attitude_control->relax_attitude_controllers();306307sub.wp_nav.wp_and_spline_init(); // Reset xy target308return;309}310311// accept pilot input of yaw312float target_yaw_rate = 0;313if (!sub.failsafe.pilot_input) {314target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());315}316317// set motors to full range318motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);319320// run waypoint and z-axis position controller321sub.failsafe_terrain_set_status(sub.wp_nav.update_wpnav());322323///////////////////////324// update xy outputs //325float lateral_out, forward_out;326sub.translate_wpnav_rp(lateral_out, forward_out);327328// Send to forward/lateral outputs329motors.set_lateral(lateral_out);330motors.set_forward(forward_out);331332// WP_Nav has set the vertical position control targets333// run the vertical position controller and set output throttle334position_control->update_z_controller();335336// get pilot desired lean angles337float target_roll, target_pitch;338sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);339340// roll & pitch & yaw rate from pilot341attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);342}343344345// set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode346void ModeAuto::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle)347{348// get current yaw349int32_t curr_yaw_target = attitude_control->get_att_target_euler_cd().z;350351// get final angle, 1 = Relative, 0 = Absolute352if (relative_angle == 0) {353// absolute angle354sub.yaw_look_at_heading = wrap_360_cd(angle_deg * 100);355} else {356// relative angle357if (direction < 0) {358angle_deg = -angle_deg;359}360sub.yaw_look_at_heading = wrap_360_cd((angle_deg * 100 + curr_yaw_target));361}362363// get turn speed364if (is_zero(turn_rate_dps)) {365// default to regular auto slew rate366sub.yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE;367} else {368sub.yaw_look_at_heading_slew = MIN(turn_rate_dps, AUTO_YAW_SLEW_RATE); // deg / sec369}370371// set yaw mode372set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);373374// TO-DO: restore support for clockwise and counter clockwise rotation held in cmd.content.yaw.direction. 1 = clockwise, -1 = counterclockwise375}376377378// sets the desired yaw rate379void ModeAuto::set_yaw_rate(float turn_rate_dps)380{381// set sub to desired yaw rate382sub.yaw_look_at_heading_slew = MIN(turn_rate_dps, AUTO_YAW_SLEW_RATE); // deg / sec383384// set yaw mode385set_auto_yaw_mode(AUTO_YAW_RATE);386}387388// set_auto_yaw_roi - sets the yaw to look at roi for auto mode389void ModeAuto::set_auto_yaw_roi(const Location &roi_location)390{391// if location is zero lat, lon and altitude turn off ROI392if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {393// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command394set_auto_yaw_mode(get_default_auto_yaw_mode(false));395#if HAL_MOUNT_ENABLED396// switch off the camera tracking if enabled397sub.camera_mount.clear_roi_target();398#endif // HAL_MOUNT_ENABLED399} else {400#if HAL_MOUNT_ENABLED401// check if mount type requires us to rotate the sub402if (!sub.camera_mount.has_pan_control()) {403if (roi_location.get_vector_from_origin_NEU(sub.roi_WP)) {404set_auto_yaw_mode(AUTO_YAW_ROI);405}406}407// send the command to the camera mount408sub.camera_mount.set_roi_target(roi_location);409410// TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)411// 0: do nothing412// 1: point at next waypoint413// 2: point at a waypoint taken from WP# parameter (2nd parameter?)414// 3: point at a location given by alt, lon, lat parameters415// 4: point at a target given a target id (can't be implemented)416#else417// if we have no camera mount aim the sub at the location418if (roi_location.get_vector_from_origin_NEU(sub.roi_WP)) {419set_auto_yaw_mode(AUTO_YAW_ROI);420}421#endif // HAL_MOUNT_ENABLED422}423}424425// Return true if it is possible to recover from a rangefinder failure426bool ModeAuto::auto_terrain_recover_start()427{428#if AP_RANGEFINDER_ENABLED429// Check rangefinder status to see if recovery is possible430switch (sub.rangefinder.status_orient(ROTATION_PITCH_270)) {431432case RangeFinder::Status::OutOfRangeLow:433case RangeFinder::Status::OutOfRangeHigh:434435// RangeFinder::Good if just one valid sample was obtained recently, but ::rangefinder_state.alt_healthy436// requires several consecutive valid readings for wpnav to accept rangefinder data437case RangeFinder::Status::Good:438sub.auto_mode = Auto_TerrainRecover;439break;440441// Not connected or no data442default:443return false; // Rangefinder is not connected, or has stopped responding444}445446// Initialize recovery timeout time447sub.fs_terrain_recover_start_ms = AP_HAL::millis();448449// Stop mission450sub.mission.stop();451452// Reset xy target453sub.loiter_nav.clear_pilot_desired_acceleration();454sub.loiter_nav.init_target();455456// Reset z axis controller457position_control->relax_z_controller(motors.get_throttle_hover());458459// initialize vertical maximum speeds and acceleration460position_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());461position_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());462463gcs().send_text(MAV_SEVERITY_WARNING, "Attempting auto failsafe recovery");464return true;465#else466return false;467#endif468}469470// Attempt recovery from terrain failsafe471// If recovery is successful resume mission472// If recovery fails revert to failsafe action473void ModeAuto::auto_terrain_recover_run()474{475float target_climb_rate = 0;476477// if not armed set throttle to zero and exit immediately478if (!motors.armed()) {479motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);480attitude_control->set_throttle_out(0,true,g.throttle_filt);481attitude_control->relax_attitude_controllers();482483sub.loiter_nav.init_target(); // Reset xy target484position_control->relax_z_controller(motors.get_throttle_hover()); // Reset z axis controller485return;486}487488#if AP_RANGEFINDER_ENABLED489static uint32_t rangefinder_recovery_ms = 0;490switch (sub.rangefinder.status_orient(ROTATION_PITCH_270)) {491492case RangeFinder::Status::OutOfRangeLow:493target_climb_rate = sub.wp_nav.get_default_speed_up();494rangefinder_recovery_ms = 0;495break;496497case RangeFinder::Status::OutOfRangeHigh:498target_climb_rate = sub.wp_nav.get_default_speed_down();499rangefinder_recovery_ms = 0;500break;501502case RangeFinder::Status::Good: // exit on success (recovered rangefinder data)503504target_climb_rate = 0; // Attempt to hold current depth505506if (sub.rangefinder_state.alt_healthy) {507508// Start timer as soon as rangefinder is healthy509if (rangefinder_recovery_ms == 0) {510rangefinder_recovery_ms = AP_HAL::millis();511position_control->relax_z_controller(motors.get_throttle_hover()); // Reset alt hold targets512}513514// 1.5 seconds of healthy rangefinder means we can resume mission with terrain enabled515if (AP_HAL::millis() > rangefinder_recovery_ms + 1500) {516gcs().send_text(MAV_SEVERITY_INFO, "Terrain failsafe recovery successful!");517sub.failsafe_terrain_set_status(true); // Reset failsafe timers518sub.failsafe.terrain = false; // Clear flag519sub.auto_mode = Auto_Loiter; // Switch back to loiter for next iteration520sub.mission.resume(); // Resume mission521rangefinder_recovery_ms = 0; // Reset for subsequent recoveries522}523524}525break;526527// Not connected, or no data528default:529// Terrain failsafe recovery has failed, terrain data is not available530// and rangefinder is not connected, or has stopped responding531gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!");532sub.failsafe_terrain_act();533rangefinder_recovery_ms = 0;534return;535}536#else537gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!");538sub.failsafe_terrain_act();539#endif540541// exit on failure (timeout)542if (AP_HAL::millis() > sub.fs_terrain_recover_start_ms + FS_TERRAIN_RECOVER_TIMEOUT_MS) {543// Recovery has failed, revert to failsafe action544gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery timeout!");545sub.failsafe_terrain_act();546}547548// run loiter controller549sub.loiter_nav.update();550551///////////////////////552// update xy targets //553float lateral_out, forward_out;554sub.translate_wpnav_rp(lateral_out, forward_out);555556// Send to forward/lateral outputs557motors.set_lateral(lateral_out);558motors.set_forward(forward_out);559560/////////////////////561// update z target //562position_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate);563position_control->update_z_controller();564565////////////////////////////566// update angular targets //567float target_roll = 0;568float target_pitch = 0;569570// convert pilot input to lean angles571// To-Do: convert sub.get_pilot_desired_lean_angles to return angles as floats572sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);573574float target_yaw_rate = 0;575576// call attitude controller577attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);578}579580581