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/Rover/mode_dock.cpp
Views: 1798
#include "Rover.h"12#if MODE_DOCK_ENABLED34const AP_Param::GroupInfo ModeDock::var_info[] = {5// @Param: _SPEED6// @DisplayName: Dock mode speed7// @Description: Vehicle speed limit in dock mode8// @Units: m/s9// @Range: 0 10010// @Increment: 0.111// @User: Standard12AP_GROUPINFO("_SPEED", 1, ModeDock, speed, 0.0f),1314// @Param: _DIR15// @DisplayName: Dock mode direction of approach16// @Description: Compass direction in which vehicle should approach towards dock. -1 value represents unset parameter17// @Units: deg18// @Range: 0 36019// @Increment: 120// @User: Advanced21AP_GROUPINFO("_DIR", 2, ModeDock, desired_dir, -1.00f),2223// @Param: _HDG_CORR_EN24// @DisplayName: Dock mode heading correction enable/disable25// @Description: When enabled, the autopilot modifies the path to approach the target head-on along desired line of approch in dock mode26// @Values: 0:Disabled,1:Enabled27// @User: Advanced28AP_GROUPINFO("_HDG_CORR_EN", 3, ModeDock, hdg_corr_enable, 0),2930// @Param: _HDG_CORR_WT31// @DisplayName: Dock mode heading correction weight32// @Description: This value describes how aggressively vehicle tries to correct its heading to be on desired line of approach33// @Range: 0.00 0.9034// @Increment: 0.0535// @User: Advanced36AP_GROUPINFO("_HDG_CORR_WT", 4, ModeDock, hdg_corr_weight, 0.75f),3738// @Param: _STOP_DIST39// @DisplayName: Distance from docking target when we should stop40// @Description: The vehicle starts stopping when it is this distance away from docking target41// @Units: m42// @Range: 0 243// @Increment: 0.0144// @User: Standard45AP_GROUPINFO("_STOP_DIST", 5, ModeDock, stopping_dist, 0.30f),4647AP_GROUPEND48};4950ModeDock::ModeDock(void) : Mode()51{52AP_Param::setup_object_defaults(this, var_info);53}5455#define AR_DOCK_ACCEL_MAX 20.0 // acceleration used when user has specified no acceleration limit5657// initialize dock mode58bool ModeDock::_enter()59{60// refuse to enter the mode if dock is not in sight61if (!rover.precland.enabled() || !rover.precland.target_acquired()) {62gcs().send_text(MAV_SEVERITY_NOTICE, "Dock: target not acquired");63return false;64}6566if (hdg_corr_enable && is_negative(desired_dir)) {67// DOCK_DIR is required for heading correction68gcs().send_text(MAV_SEVERITY_NOTICE, "Dock: Set DOCK_DIR or disable heading correction");69return false;70}7172// set speed limit to dock_speed param if available73// otherwise the vehicle uses wp_nav default speed limit74const float speed_max = is_positive(speed) ? speed : g2.wp_nav.get_default_speed();75float atc_accel_max = MIN(g2.attitude_control.get_accel_max(), g2.attitude_control.get_decel_max());76if (!is_positive(atc_accel_max)) {77// accel_max of zero means no limit so use maximum acceleration78atc_accel_max = AR_DOCK_ACCEL_MAX;79}80const float accel_max = is_positive(g2.wp_nav.get_default_accel()) ? MIN(g2.wp_nav.get_default_accel(), atc_accel_max) : atc_accel_max;81const float jerk_max = is_positive(g2.wp_nav.get_default_jerk()) ? g2.wp_nav.get_default_jerk() : accel_max;8283// initialise position controller84g2.pos_control.set_limits(speed_max, accel_max, g2.attitude_control.get_turn_lat_accel_max(), jerk_max);85g2.pos_control.init();8687// set the position controller reversed in case the camera is mounted on vehicle's back88g2.pos_control.set_reversed(rover.precland.get_orient() == 4);8990// construct unit vector in the desired direction from where we want the vehicle to approach the dock91// this helps to dock the vehicle head-on even when we enter the dock mode at an angle towards the dock92_desired_heading_NE = Vector2f{cosf(radians(desired_dir)), sinf(radians(desired_dir))};9394_docking_complete = false;9596return true;97}9899void ModeDock::update()100{101// if docking is complete, rovers stop and boats loiter102if (_docking_complete) {103// rovers stop, boats loiter104// note that loiter update must be called after successfull initialisation on mode loiter105if (_loitering) {106// mode loiter must be initialised before calling update method107rover.mode_loiter.update();108} else {109stop_vehicle();110}111return;112}113114const bool real_dock_in_sight = rover.precland.get_target_position_cm(_dock_pos_rel_origin_cm);115Vector2f dock_pos_rel_vehicle_cm;116if (!calc_dock_pos_rel_vehicle_NE(dock_pos_rel_vehicle_cm)) {117g2.motors.set_throttle(0.0f);118g2.motors.set_steering(0.0f);119return;120}121122_distance_to_destination = dock_pos_rel_vehicle_cm.length() * 0.01f;123124// we force the vehicle to use real dock as target when we are too close to the dock125// note that heading correction does not work when we force real target126const bool force_real_target = _distance_to_destination < _force_real_target_limit_cm * 0.01f;127128// if we are close enough to the dock or the target is not in sight when we strictly require it129// we mark the docking to be completed so that the vehicle stops130if (_distance_to_destination <= stopping_dist || (force_real_target && !real_dock_in_sight)) {131_docking_complete = true;132133// send a one time notification to GCS134gcs().send_text(MAV_SEVERITY_INFO, "Dock: Docking complete");135136// initialise mode loiter if it is a boat137if (rover.is_boat()) {138// if we fail to enter, we set _loitering to false139_loitering = rover.mode_loiter.enter();140}141return;142}143144Vector2f target_cm = _dock_pos_rel_origin_cm;145146// ***** HEADING CORRECTION *****147// to make to vehicle dock from a given direction we simulate a virtual moving target on the line of approach148// this target is always at DOCK_HDG_COR_WT times the distance from dock to vehicle (along the line of approach)149// For e.g., if the dock is 100 m away form dock, DOCK_HDG_COR_WT is 0.75150// then the position target is 75 m from the dock, i.e., 25 m from the vehicle151// as the vehicle tries to reach this target, this target appears to move towards the dock and at last it is sandwiched b/w dock and vehicle152// since this target is moving along desired direction of approach, the vehicle also comes on that line while following it153if (!force_real_target && hdg_corr_enable) {154const float correction_vec_mag = hdg_corr_weight * dock_pos_rel_vehicle_cm.projected(_desired_heading_NE).length();155target_cm = _dock_pos_rel_origin_cm - _desired_heading_NE * correction_vec_mag;156}157158const Vector2p target_pos { target_cm.topostype() * 0.01 };159g2.pos_control.input_pos_target(target_pos, rover.G_Dt);160g2.pos_control.update(rover.G_Dt);161162// get desired speed and turn rate from pos_control163float desired_speed = g2.pos_control.get_desired_speed();164float desired_turn_rate = g2.pos_control.get_desired_turn_rate_rads();165166// slow down the vehicle as we approach the dock167desired_speed = apply_slowdown(desired_speed);168169// run steering and throttle controllers170calc_steering_from_turn_rate(desired_turn_rate);171calc_throttle(desired_speed, true);172173#if HAL_LOGGING_ENABLED174// @LoggerMessage: DOCK175// @Description: Dock mode target information176// @Field: TimeUS: Time since system startup177// @Field: DockX: Docking Station position, X-Axis178// @Field: DockY: Docking Station position, Y-Axis179// @Field: DockDist: Distance to docking station180// @Field: TPosX: Current Position Target, X-Axis181// @Field: TPosY: Current Position Target, Y-Axis182// @Field: DSpd: Desired speed183// @Field: DTrnRt: Desired Turn Rate184185AP::logger().WriteStreaming(186"DOCK",187"TimeUS,DockX,DockY,DockDist,TPosX,TPosY,DSpd,DTrnRt",188"smmmmmnE",189"FBB0BB00",190"Qfffffff",191AP_HAL::micros64(),192_dock_pos_rel_origin_cm.x,193_dock_pos_rel_origin_cm.y,194_distance_to_destination,195target_cm.x,196target_cm.y,197desired_speed,198desired_turn_rate);199#endif200}201202float ModeDock::apply_slowdown(float desired_speed)203{204const float dock_speed_slowdown_lmt = 0.5f;205206// no slowdown for speed below dock_speed_slowdown_lmt207if (fabsf(desired_speed) < dock_speed_slowdown_lmt) {208return desired_speed;209}210211Vector3f target_vec_rel_vehicle_NED;212if(!calc_dock_pos_rel_vehicle_NE(target_vec_rel_vehicle_NED.xy())) {213return desired_speed;214}215216const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned();217Vector3f target_vec_body = body_to_ned.mul_transpose(target_vec_rel_vehicle_NED);218const float target_error_cm = fabsf(target_vec_body.y);219float error_ratio = target_error_cm / _acceptable_pos_error_cm;220error_ratio = constrain_float(error_ratio, 0.0f, 1.0f);221222const float dock_slow_dist_max_m = 15.0f;223const float dock_slow_dist_min_m = 5.0f;224// approach slowdown is not applied when the vehicle is more than dock_slow_dist_max meters away225// within dock_slow_dist_max and dock_slow_dist_min the weight of the slowdown increases linearly226// once the vehicle reaches dock_slow_dist_min the slowdown weight becomes 1227float slowdown_weight = 1 - (target_vec_body.x * 0.01f - dock_slow_dist_min_m) / (dock_slow_dist_max_m - dock_slow_dist_min_m);228slowdown_weight = constrain_float(slowdown_weight, 0.0f, 1.0f);229230desired_speed = MAX(dock_speed_slowdown_lmt, fabsf(desired_speed) * (1 - error_ratio * slowdown_weight));231232// restrict speed to avoid going beyond stopping distance233desired_speed = MIN(desired_speed, safe_sqrt(2 * fabsf(_distance_to_destination - stopping_dist) * g2.pos_control.get_accel_max()));234235// we worked on absolute value of speed before236// make it negative again if reversed237if (g2.pos_control.get_reversed()) {238desired_speed *= -1;239}240241return desired_speed;242}243244// calculate position of dock relative to the vehicle245// we need this method here because there can be a window during heading correction when we might lose the target246// during that window precland won't be able to give us this vector247// we can calculate it based on most recent value from precland because the dock is assumed stationary wrt ekf origin248bool ModeDock::calc_dock_pos_rel_vehicle_NE(Vector2f &dock_pos_rel_vehicle) const {249Vector2f current_pos_m;250if (!AP::ahrs().get_relative_position_NE_origin(current_pos_m)) {251return false;252}253254dock_pos_rel_vehicle = _dock_pos_rel_origin_cm - current_pos_m * 100.0f;255return true;256}257#endif // MODE_DOCK_ENABLED258259260