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_circle.cpp
Views: 1798
#include "Rover.h"12#define AR_CIRCLE_ACCEL_DEFAULT 1.0 // default acceleration in m/s/s if not specified by user3#define AR_CIRCLE_RADIUS_MIN 0.5 // minimum radius in meters4#define AR_CIRCLE_REACHED_EDGE_DIST 0.2 // vehicle has reached edge if within 0.2m56const AP_Param::GroupInfo ModeCircle::var_info[] = {78// @Param: _RADIUS9// @DisplayName: Circle Radius10// @Description: Vehicle will circle the center at this distance11// @Units: m12// @Range: 0 10013// @Increment: 114// @User: Standard15AP_GROUPINFO("_RADIUS", 1, ModeCircle, radius, 20),1617// @Param: _SPEED18// @DisplayName: Circle Speed19// @Description: Vehicle will move at this speed around the circle. If set to zero WP_SPEED will be used20// @Units: m/s21// @Range: 0 1022// @Increment: 0.123// @User: Standard24AP_GROUPINFO("_SPEED", 2, ModeCircle, speed, 0),2526// @Param: _DIR27// @DisplayName: Circle Direction28// @Description: Circle Direction29// @Values: 0:Clockwise, 1:Counter-Clockwise30// @User: Standard31AP_GROUPINFO("_DIR", 3, ModeCircle, direction, 0),3233AP_GROUPEND34};3536ModeCircle::ModeCircle() : Mode()37{38AP_Param::setup_object_defaults(this, var_info);39}4041// initialise with specific center location, radius (in meters) and direction42// replaces use of _enter when initialised from within Auto mode43bool ModeCircle::set_center(const Location& center_loc, float radius_m, bool dir_ccw)44{45Vector2f center_pos_cm;46if (!center_loc.get_vector_xy_from_origin_NE(center_pos_cm)) {47return false;48}49if (!_enter()) {50return false;51}5253// convert center position from cm to m54config.center_pos = center_pos_cm * 0.01;5556// set radius57config.radius = MAX(fabsf(radius_m), AR_CIRCLE_RADIUS_MIN);58check_config_radius();5960// set direction61config.dir = dir_ccw ? Direction::CCW : Direction::CW;6263// set target yaw rad (target point on circle)64init_target_yaw_rad();6566// record center as location (only used for reporting)67config.center_loc = center_loc;6869return true;70}7172// initialize circle mode from current position73bool ModeCircle::_enter()74{75// capture starting point and yaw76if (!AP::ahrs().get_relative_position_NE_origin(config.center_pos)) {77return false;78}79config.radius = MAX(fabsf(radius), AR_CIRCLE_RADIUS_MIN);80check_config_radius();8182config.dir = (direction == 1) ? Direction::CCW : Direction::CW;83config.speed = is_positive(speed) ? speed : g2.wp_nav.get_default_speed();84target.yaw_rad = AP::ahrs().get_yaw();85target.speed = 0;8687// record center as location (only used for reporting)88config.center_loc = rover.current_loc;8990// check speed around circle does not lead to excessive lateral acceleration91check_config_speed();9293// reset tracking_back94tracking_back = false;9596// calculate speed, accel and jerk limits97// otherwise the vehicle uses wp_nav default speed limit98float atc_accel_max = MIN(g2.attitude_control.get_accel_max(), g2.attitude_control.get_decel_max());99if (!is_positive(atc_accel_max)) {100atc_accel_max = AR_CIRCLE_ACCEL_DEFAULT;101}102const float accel_max = is_positive(g2.wp_nav.get_default_accel()) ? MIN(g2.wp_nav.get_default_accel(), atc_accel_max) : atc_accel_max;103const float jerk_max = is_positive(g2.wp_nav.get_default_jerk()) ? g2.wp_nav.get_default_jerk() : accel_max;104105// initialise position controller106g2.pos_control.set_limits(config.speed, accel_max, g2.attitude_control.get_turn_lat_accel_max(), jerk_max);107g2.pos_control.init();108109// initialise angles covered and reached_edge state110angle_total_rad = 0;111reached_edge = false;112dist_to_edge_m = 0;113114return true;115}116117// initialise target_yaw_rad using the vehicle's position and yaw118// if there is no current position estimate target_yaw_rad is set to 0119void ModeCircle::init_target_yaw_rad()120{121// if no position estimate use vehicle yaw122Vector2f curr_pos_NE;123if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {124target.yaw_rad = AP::ahrs().get_yaw();125return;126}127128// calc vector from circle center to vehicle129Vector2f center_to_veh = (curr_pos_NE - config.center_pos);130float dist_m = center_to_veh.length();131132// if current position is exactly at the center of the circle return vehicle yaw133if (is_zero(dist_m)) {134target.yaw_rad = AP::ahrs().get_yaw();135} else {136target.yaw_rad = center_to_veh.angle();137}138}139140void ModeCircle::update()141{142// get current position143Vector2f curr_pos;144const bool position_ok = AP::ahrs().get_relative_position_NE_origin(curr_pos);145146// if no position estimate stop vehicle147if (!position_ok) {148stop_vehicle();149return;150}151152// Update distance to destination and distance to edge153const Vector2f center_to_veh = curr_pos - config.center_pos;154_distance_to_destination = (target.pos.tofloat() - curr_pos).length();155dist_to_edge_m = fabsf(center_to_veh.length() - config.radius);156157// Update depending on stage158if (!reached_edge) {159update_drive_to_radius();160} else if (dist_to_edge_m > 2 * MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST) && !tracking_back) {161// if more than 2* turn_radius outside circle radius, slow vehicle by 20%162config.speed = 0.8 * config.speed;163GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Circle: cannot keep up, slowing to %.1fm/s", config.speed);164tracking_back = true;165} else if (dist_to_edge_m < MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST) && tracking_back) {166// if within turn_radius, call the vehicle back on track167tracking_back = false;168} else {169update_circling();170}171172g2.pos_control.update(rover.G_Dt);173174// get desired speed and turn rate from pos_control175const float desired_speed = g2.pos_control.get_desired_speed();176const float desired_turn_rate = g2.pos_control.get_desired_turn_rate_rads();177178// run steering and throttle controllers179calc_steering_from_turn_rate(desired_turn_rate);180calc_throttle(desired_speed, true);181}182183void ModeCircle::update_drive_to_radius()184{185// check if vehicle has reached edge of circle186const float dist_thresh_m = MAX(g2.turn_radius, AR_CIRCLE_REACHED_EDGE_DIST);187reached_edge |= dist_to_edge_m <= dist_thresh_m;188189// calculate target point's position, velocity and acceleration190target.pos = config.center_pos.topostype();191target.pos.offset_bearing(degrees(target.yaw_rad), config.radius);192193g2.pos_control.input_pos_target(target.pos, rover.G_Dt);194}195196// Update position controller targets while circling197void ModeCircle::update_circling()198{199200// accelerate speed up to desired speed201const float speed_change_max = (g2.pos_control.get_accel_max() * 0.5 * rover.G_Dt);202const float accel_fb = constrain_float(config.speed - target.speed, -speed_change_max, speed_change_max);203target.speed += accel_fb;204205// calculate angular rate and update target angle, if the vehicle is not trying to track back206if (!tracking_back) {207const float circumference = 2.0 * M_PI * config.radius;208const float angular_rate_rad = (target.speed / circumference) * M_2PI * (config.dir == Direction::CW ? 1.0 : -1.0);209const float angle_dt = angular_rate_rad * rover.G_Dt;210target.yaw_rad = wrap_PI(target.yaw_rad + angle_dt);211angle_total_rad += angle_dt;212} else {213init_target_yaw_rad();214}215216// calculate target point's position, velocity and acceleration217target.pos = config.center_pos.topostype();218target.pos.offset_bearing(degrees(target.yaw_rad), config.radius);219220// velocity is perpendicular to angle from the circle's center to the target point on the edge of the circle221target.vel = Vector2f(target.speed, 0);222target.vel.rotate(target.yaw_rad + radians(90));223224// acceleration is towards center of circle and is speed^2 / radius225target.accel = Vector2f(-sq(target.speed) / config.radius, accel_fb / rover.G_Dt);226target.accel.rotate(target.yaw_rad);227228g2.pos_control.set_pos_vel_accel_target(target.pos, target.vel, target.accel);229230}231232// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)233float ModeCircle::wp_bearing() const234{235Vector2f curr_pos_NE;236if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {237return 0;238}239// calc vector from circle center to vehicle240Vector2f veh_to_center = (target.pos.tofloat() - curr_pos_NE);241if (veh_to_center.is_zero()) {242return 0;243}244return degrees(veh_to_center.angle());245}246247float ModeCircle::nav_bearing() const248{249// get position error as a vector from the current position to the target position250const Vector2p pos_error = g2.pos_control.get_pos_error();251if (pos_error.is_zero()) {252return 0;253}254return degrees(pos_error.angle());255}256257float ModeCircle::get_desired_lat_accel() const258{259return g2.pos_control.get_desired_lat_accel();260}261262// set desired speed in m/s263bool ModeCircle::set_desired_speed(float speed_ms)264{265if (is_positive(speed_ms)) {266config.speed = speed_ms;267268// check desired speed does not lead to excessive lateral acceleration269check_config_speed();270271// update position controller limits if required272if (config.speed > g2.pos_control.get_speed_max()) {273g2.pos_control.set_limits(config.speed, g2.pos_control.get_accel_max(), g2.pos_control.get_lat_accel_max(), g2.pos_control.get_jerk_max());274}275return true;276}277278return false;279}280281// return desired location282bool ModeCircle::get_desired_location(Location& destination) const283{284destination = config.center_loc;285destination.offset_bearing(degrees(target.yaw_rad), config.radius);286return true;287}288289// limit config speed so that lateral acceleration is within limits290// assumes that config.radius and attitude controller lat accel max have been set291// outputs warning to user if speed is reduced292void ModeCircle::check_config_speed()293{294// calculate maximum speed based on radius and max lateral acceleration max295const float speed_max = MAX(safe_sqrt(g2.attitude_control.get_turn_lat_accel_max() * config.radius), 0);296297if (config.speed > speed_max) {298config.speed = speed_max;299gcs().send_text(MAV_SEVERITY_WARNING, "Circle: max speed is %4.1f", (double)config.speed);300}301}302303// ensure config radius is no smaller then vehicle's TURN_RADIUS304// assumes that config.radius has been set305// radius is increased if necessary and warning is output to the user306void ModeCircle::check_config_radius()307{308// ensure radius is at least as large as vehicle's turn radius309if (config.radius < g2.turn_radius) {310config.radius = g2.turn_radius;311gcs().send_text(MAV_SEVERITY_WARNING, "Circle: radius increased to TURN_RADIUS (%4.1f)", (double)g2.turn_radius);312}313}314315316