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_surftrak.cpp
Views: 1798
#include "Sub.h"12/*3* SURFTRAK (surface tracking) -- a variation on ALT_HOLD (depth hold)4*5* SURFTRAK starts in the "reset" state (rangefinder_target_cm < 0). SURFTRAK exits the reset state when these6* conditions are met:7* -- There is a good rangefinder reading (the rangefinder is healthy, the reading is between min and max, etc.)8* -- The sub is below SURFTRAK_DEPTH9*10* During normal operation, SURFTRAK sets the offset target to the current terrain altitude estimate and calls11* AC_PosControl to do the rest.12*13* We generally do not want to reset SURFTRAK if the rangefinder glitches, since that will result in a new rangefinder14* target. E.g., if a pilot is running 1m above the seafloor, there is a glitch, and the next rangefinder reading shows15* 1.1m, the desired behavior is to move 10cm closer to the seafloor, vs setting a new target of 1.1m above the16* seafloor.17*18* If the pilot takes control, SURFTRAK uses the change in depth readings to adjust the rangefinder target. This19* minimizes the "bounce back" that can happen as the slower rangefinder catches up to the quicker barometer.20*/2122#define INVALID_TARGET (-1)23#define HAS_VALID_TARGET (rangefinder_target_cm > 0)2425ModeSurftrak::ModeSurftrak() :26rangefinder_target_cm(INVALID_TARGET),27pilot_in_control(false),28pilot_control_start_z_cm(0)29{ }3031bool ModeSurftrak::init(bool ignore_checks)32{33if (!ModeAlthold::init(ignore_checks)) {34return false;35}3637reset();3839if (!sub.rangefinder_alt_ok()) {40sub.gcs().send_text(MAV_SEVERITY_INFO, "waiting for a rangefinder reading");41#if AP_RANGEFINDER_ENABLED42} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {43sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to hold range", sub.g.surftrak_depth * 0.01f);44#endif45}4647return true;48}4950void ModeSurftrak::run()51{52run_pre();53control_range();54run_post();55}5657/*58* Set the rangefinder target, return true if successful. This may be called from scripting so run a few extra checks.59*/60bool ModeSurftrak::set_rangefinder_target_cm(float target_cm)61{62bool success = false;6364#if AP_RANGEFINDER_ENABLED65if (sub.control_mode != Number::SURFTRAK) {66sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set");67} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {68sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to set rangefinder target", sub.g.surftrak_depth * 0.01f);69} else if (target_cm < (float)sub.rangefinder_state.min_cm) {70sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target below minimum, ignored");71} else if (target_cm > (float)sub.rangefinder_state.max_cm) {72sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target above maximum, ignored");73} else {74success = true;75}7677if (success) {78rangefinder_target_cm = target_cm;79sub.gcs().send_text(MAV_SEVERITY_INFO, "rangefinder target is %.2f meters", rangefinder_target_cm * 0.01f);8081// Initialize the terrain offset82auto terrain_offset_cm = sub.inertial_nav.get_position_z_up_cm() - rangefinder_target_cm;83sub.pos_control.init_pos_terrain_cm(terrain_offset_cm);8485} else {86reset();87}88#endif8990return success;91}9293void ModeSurftrak::reset()94{95rangefinder_target_cm = INVALID_TARGET;9697// Reset the terrain offset98sub.pos_control.init_pos_terrain_cm(0);99}100101/*102* Main controller, call at 100hz+103*/104void ModeSurftrak::control_range() {105float target_climb_rate_cm_s = sub.get_pilot_desired_climb_rate(channel_throttle->get_control_in());106target_climb_rate_cm_s = constrain_float(target_climb_rate_cm_s, -sub.get_pilot_speed_dn(), g.pilot_speed_up);107108// Desired_climb_rate returns 0 when within the deadzone109if (fabsf(target_climb_rate_cm_s) < 0.05f) {110if (pilot_in_control) {111// Pilot has released control; apply the delta to the rangefinder target112set_rangefinder_target_cm(rangefinder_target_cm + inertial_nav.get_position_z_up_cm() - pilot_control_start_z_cm);113pilot_in_control = false;114}115if (sub.ap.at_surface) {116// Set target depth to 5 cm below SURFACE_DEPTH and reset117position_control->set_pos_desired_z_cm(MIN(position_control->get_pos_desired_z_cm(), g.surface_depth - 5.0f));118reset();119} else if (sub.ap.at_bottom) {120// Set target depth to 10 cm above bottom and reset121position_control->set_pos_desired_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_z_cm()));122reset();123} else {124// Typical operation125update_surface_offset();126}127} else if (HAS_VALID_TARGET && !pilot_in_control) {128// Pilot has taken control; note the current depth129pilot_control_start_z_cm = inertial_nav.get_position_z_up_cm();130pilot_in_control = true;131}132133// Set the target altitude from the climb rate and the terrain offset134position_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cm_s);135136// Run the PID controllers137position_control->update_z_controller();138}139140/*141* Update the AC_PosControl terrain offset if we have a good rangefinder reading142*/143void ModeSurftrak::update_surface_offset()144{145#if AP_RANGEFINDER_ENABLED146if (sub.rangefinder_alt_ok()) {147// Get the latest terrain offset148float rangefinder_terrain_offset_cm = sub.rangefinder_state.rangefinder_terrain_offset_cm;149150// Handle the first reading or a reset151if (!HAS_VALID_TARGET && sub.rangefinder_state.inertial_alt_cm < sub.g.surftrak_depth) {152set_rangefinder_target_cm(sub.rangefinder_state.inertial_alt_cm - rangefinder_terrain_offset_cm);153}154155if (HAS_VALID_TARGET) {156// Will the new offset target cause the sub to ascend above SURFTRAK_DEPTH?157float desired_z_cm = rangefinder_terrain_offset_cm + rangefinder_target_cm;158if (desired_z_cm >= sub.g.surftrak_depth) {159// Adjust the terrain offset to stay below SURFTRAK_DEPTH, this should avoid "at_surface" events160rangefinder_terrain_offset_cm += sub.g.surftrak_depth - desired_z_cm;161}162163// Set the offset target, AC_PosControl will do the rest164sub.pos_control.set_pos_terrain_target_cm(rangefinder_terrain_offset_cm);165}166}167#endif // AP_RANGEFINDER_ENABLED168}169170171