123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768 |
- #include "Sub.h"
- bool Sub::auto_init()
- {
- if (!position_ok() || mission.num_commands() < 2) {
- return false;
- }
- auto_mode = Auto_Loiter;
-
-
- if (auto_yaw_mode == AUTO_YAW_ROI) {
- set_auto_yaw_mode(AUTO_YAW_HOLD);
- }
-
- wp_nav.wp_and_spline_init();
-
- guided_limit_clear();
-
- mission.start_or_resume();
- return true;
- }
- void Sub::auto_run()
- {
- mission.update();
-
- switch (auto_mode) {
- case Auto_WP:
- case Auto_CircleMoveToEdge:
- auto_wp_run();
- break;
- case Auto_Circle:
- auto_circle_run();
- break;
- case Auto_Spline:
- auto_spline_run();
- break;
- case Auto_NavGuided:
- #if NAV_GUIDED == ENABLED
- auto_nav_guided_run();
- #endif
- break;
- case Auto_Loiter:
- auto_loiter_run();
- break;
- case Auto_TerrainRecover:
- auto_terrain_recover_run();
- break;
- }
- }
- void Sub::auto_wp_start(const Vector3f& destination)
- {
- auto_mode = Auto_WP;
-
- wp_nav.set_wp_destination(destination, false);
-
-
- if (auto_yaw_mode != AUTO_YAW_ROI) {
- set_auto_yaw_mode(get_default_auto_yaw_mode(false));
- }
- }
- void Sub::auto_wp_start(const Location& dest_loc)
- {
- auto_mode = Auto_WP;
-
- if (!wp_nav.set_wp_destination(dest_loc)) {
-
- failsafe_terrain_on_event();
- return;
- }
-
-
- if (auto_yaw_mode != AUTO_YAW_ROI) {
- set_auto_yaw_mode(get_default_auto_yaw_mode(false));
- }
- }
- void Sub::auto_wp_run()
- {
-
- if (!motors.armed()) {
-
-
-
-
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
- attitude_control.set_throttle_out(0,true,g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- return;
- }
-
- float target_yaw_rate = 0;
- if (!failsafe.pilot_input) {
-
- target_yaw_rate = 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);
-
-
-
-
- failsafe_terrain_set_status(wp_nav.update_wpnav());
-
-
- float lateral_out, forward_out;
- translate_wpnav_rp(lateral_out, forward_out);
-
- motors.set_lateral(lateral_out);
- motors.set_forward(forward_out);
-
- pos_control.update_z_controller();
-
-
-
- float target_roll, target_pitch;
- get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
-
- if (auto_yaw_mode == AUTO_YAW_HOLD) {
-
- attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
- } else {
-
- attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true);
- }
- }
- void Sub::auto_spline_start(const Location& destination, bool stopped_at_start,
- AC_WPNav::spline_segment_end_type seg_end_type,
- const Location& next_destination)
- {
- auto_mode = Auto_Spline;
-
- if (!wp_nav.set_spline_destination(destination, stopped_at_start, seg_end_type, next_destination)) {
-
- failsafe_terrain_on_event();
- return;
- }
-
-
- if (auto_yaw_mode != AUTO_YAW_ROI) {
- set_auto_yaw_mode(get_default_auto_yaw_mode(false));
- }
- }
- void Sub::auto_spline_run()
- {
-
- if (!motors.armed()) {
-
-
-
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
- attitude_control.set_throttle_out(0,true,g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- return;
- }
-
- float target_yaw_rate = 0;
- if (!failsafe.pilot_input) {
-
- target_yaw_rate = 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);
-
- wp_nav.update_spline();
- float lateral_out, forward_out;
- translate_wpnav_rp(lateral_out, forward_out);
-
- motors.set_lateral(lateral_out);
- motors.set_forward(forward_out);
-
- pos_control.update_z_controller();
-
- float target_roll, target_pitch;
- get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
-
- if (auto_yaw_mode == AUTO_YAW_HOLD) {
-
- attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
- } else {
-
- attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true);
- }
- }
- void Sub::auto_circle_movetoedge_start(const Location &circle_center, float radius_m)
- {
-
- Vector3f circle_center_neu;
- if (!circle_center.get_vector_from_origin_NEU(circle_center_neu)) {
-
- circle_center_neu = inertial_nav.get_position();
- AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
- }
- circle_nav.set_center(circle_center_neu);
-
- if (!is_zero(radius_m)) {
- circle_nav.set_radius(radius_m * 100.0f);
- }
-
- Vector3f circle_edge_neu;
- circle_nav.get_closest_point_on_circle(circle_edge_neu);
- float dist_to_edge = (inertial_nav.get_position() - circle_edge_neu).length();
-
- if (dist_to_edge > 300.0f) {
-
- auto_mode = Auto_CircleMoveToEdge;
-
- Location circle_edge(circle_edge_neu);
-
- circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());
-
- if (!wp_nav.set_wp_destination(circle_edge)) {
-
- failsafe_terrain_on_event();
- }
-
- const Vector3f &curr_pos = inertial_nav.get_position();
- float dist_to_center = norm(circle_center_neu.x - curr_pos.x, circle_center_neu.y - curr_pos.y);
- if (dist_to_center > circle_nav.get_radius() && 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 Sub::auto_circle_start()
- {
- auto_mode = Auto_Circle;
-
- circle_nav.init(circle_nav.get_center());
- }
- void Sub::auto_circle_run()
- {
-
- circle_nav.update();
- float lateral_out, forward_out;
- translate_circle_nav_rp(lateral_out, forward_out);
-
- motors.set_lateral(lateral_out);
- motors.set_forward(forward_out);
-
- pos_control.update_z_controller();
-
- attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true);
- }
- #if NAV_GUIDED == ENABLED
- void Sub::auto_nav_guided_start()
- {
- auto_mode = Auto_NavGuided;
-
- guided_init(true);
-
- guided_limit_init_time_and_pos();
- }
- void Sub::auto_nav_guided_run()
- {
-
- guided_run();
- }
- #endif
- bool Sub::auto_loiter_start()
- {
-
- if (!position_ok()) {
- return false;
- }
- auto_mode = Auto_Loiter;
- Vector3f origin = inertial_nav.get_position();
-
- Vector3f stopping_point;
- pos_control.get_stopping_point_xy(stopping_point);
- pos_control.get_stopping_point_z(stopping_point);
-
- wp_nav.set_wp_origin_and_destination(origin, stopping_point);
-
- set_auto_yaw_mode(AUTO_YAW_HOLD);
- return true;
- }
- void Sub::auto_loiter_run()
- {
-
- if (!motors.armed()) {
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
-
- attitude_control.set_throttle_out(0,true,g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- return;
- }
-
- float target_yaw_rate = 0;
- if (!failsafe.pilot_input) {
- target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
- }
-
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
-
- failsafe_terrain_set_status(wp_nav.update_wpnav());
-
-
- float lateral_out, forward_out;
- translate_wpnav_rp(lateral_out, forward_out);
-
- motors.set_lateral(lateral_out);
- motors.set_forward(forward_out);
-
- pos_control.update_z_controller();
-
- float target_roll, target_pitch;
- get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
-
- attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
- }
- uint8_t Sub::get_default_auto_yaw_mode(bool rtl)
- {
- 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 Sub::set_auto_yaw_mode(uint8_t yaw_mode)
- {
-
- if (auto_yaw_mode == yaw_mode) {
- return;
- }
- auto_yaw_mode = yaw_mode;
-
- switch (auto_yaw_mode) {
- case AUTO_YAW_LOOK_AT_NEXT_WP:
-
- break;
- case AUTO_YAW_ROI:
-
- yaw_look_at_WP_bearing = ahrs.yaw_sensor;
- break;
- case AUTO_YAW_LOOK_AT_HEADING:
-
-
- break;
- case AUTO_YAW_LOOK_AHEAD:
-
- yaw_look_ahead_bearing = ahrs.yaw_sensor;
- break;
- case AUTO_YAW_RESETTOARMEDYAW:
-
- break;
- }
- }
- void Sub::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) {
-
- yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
- } else {
-
- if (direction < 0) {
- angle_deg = -angle_deg;
- }
- yaw_look_at_heading = wrap_360_cd((angle_deg*100+curr_yaw_target));
- }
-
-
-
- if (is_zero(turn_rate_dps)) {
-
- yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE;
- } else {
- int32_t turn_rate = (wrap_180_cd(yaw_look_at_heading - curr_yaw_target) / 100) / turn_rate_dps;
- yaw_look_at_heading_slew = constrain_int32(turn_rate, 1, 360);
- }
-
- set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
-
- }
- void Sub::set_auto_yaw_roi(const Location &roi_location)
- {
-
- if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {
-
- set_auto_yaw_mode(get_default_auto_yaw_mode(false));
- #if MOUNT == ENABLED
-
- if (camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
- camera_mount.set_mode_to_default();
- }
- #endif
- } else {
- #if MOUNT == ENABLED
-
- if (!camera_mount.has_pan_control()) {
- roi_WP = pv_location_to_vector(roi_location);
- set_auto_yaw_mode(AUTO_YAW_ROI);
- }
-
- camera_mount.set_roi_target(roi_location);
-
-
-
-
-
-
- #else
-
- roi_WP = pv_location_to_vector(roi_location);
- set_auto_yaw_mode(AUTO_YAW_ROI);
- #endif
- }
- }
- float Sub::get_auto_heading()
- {
- switch (auto_yaw_mode) {
- case AUTO_YAW_ROI:
-
- return get_roi_yaw();
- break;
- case AUTO_YAW_LOOK_AT_HEADING:
-
- return yaw_look_at_heading;
- break;
- case AUTO_YAW_LOOK_AHEAD:
-
- return get_look_ahead_yaw();
- break;
- case AUTO_YAW_RESETTOARMEDYAW:
-
- return initial_armed_bearing;
- break;
- case AUTO_YAW_CORRECT_XTRACK: {
-
-
- float track_bearing = get_bearing_cd(wp_nav.get_wp_origin(), wp_nav.get_wp_destination());
-
- float desired_angle = pos_control.get_bearing_to_target();
- float angle_error = wrap_180_cd(desired_angle - 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 wp_nav.get_yaw();
- break;
- }
- }
- bool Sub::auto_terrain_recover_start()
- {
-
- switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
- case RangeFinder::RangeFinder_OutOfRangeLow:
- case RangeFinder::RangeFinder_OutOfRangeHigh:
-
-
- case RangeFinder::RangeFinder_Good:
- auto_mode = Auto_TerrainRecover;
- break;
-
- default:
- return false;
- }
-
- fs_terrain_recover_start_ms = AP_HAL::millis();
-
- mission.stop();
-
- loiter_nav.clear_pilot_desired_acceleration();
- loiter_nav.init_target();
-
- pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
-
- pos_control.set_max_speed_z(wp_nav.get_default_speed_down(), wp_nav.get_default_speed_up());
- pos_control.set_max_accel_z(wp_nav.get_accel_z());
-
- pos_control.set_alt_target(inertial_nav.get_altitude());
- pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
- gcs().send_text(MAV_SEVERITY_WARNING, "Attempting auto failsafe recovery");
- return true;
- }
- void Sub::auto_terrain_recover_run()
- {
- float target_climb_rate = 0;
- static uint32_t rangefinder_recovery_ms = 0;
-
- if (!motors.armed()) {
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
- attitude_control.set_throttle_out(0,true,g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- return;
- }
- switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
- case RangeFinder::RangeFinder_OutOfRangeLow:
- target_climb_rate = wp_nav.get_default_speed_up();
- rangefinder_recovery_ms = 0;
- break;
- case RangeFinder::RangeFinder_OutOfRangeHigh:
- target_climb_rate = wp_nav.get_default_speed_down();
- rangefinder_recovery_ms = 0;
- break;
- case RangeFinder::RangeFinder_Good:
- target_climb_rate = 0;
- if (rangefinder_state.alt_healthy) {
-
- if (rangefinder_recovery_ms == 0) {
- rangefinder_recovery_ms = AP_HAL::millis();
- pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
- }
-
- if (AP_HAL::millis() > rangefinder_recovery_ms + 1500) {
- gcs().send_text(MAV_SEVERITY_INFO, "Terrain failsafe recovery successful!");
- failsafe_terrain_set_status(true);
- failsafe.terrain = false;
- auto_mode = Auto_Loiter;
- mission.resume();
- rangefinder_recovery_ms = 0;
- }
- }
- break;
-
- default:
-
-
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery failure: No Rangefinder!");
- failsafe_terrain_act();
- rangefinder_recovery_ms = 0;
- return;
- }
-
- if (AP_HAL::millis() > fs_terrain_recover_start_ms + FS_TERRAIN_RECOVER_TIMEOUT_MS) {
-
- gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain failsafe recovery timeout!");
- failsafe_terrain_act();
- }
-
- loiter_nav.update();
-
-
- float lateral_out, forward_out;
- translate_wpnav_rp(lateral_out, forward_out);
-
- motors.set_lateral(lateral_out);
- motors.set_forward(forward_out);
-
-
- pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, true);
- pos_control.update_z_controller();
-
-
- float target_roll = 0;
- float target_pitch = 0;
-
-
- get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
- float target_yaw_rate = 0;
-
- attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
- }
|