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.cpp
Views: 1798
#include "Rover.h"12Mode::Mode() :3ahrs(rover.ahrs),4g(rover.g),5g2(rover.g2),6channel_steer(rover.channel_steer),7channel_throttle(rover.channel_throttle),8channel_lateral(rover.channel_lateral),9channel_roll(rover.channel_roll),10channel_pitch(rover.channel_pitch),11channel_walking_height(rover.channel_walking_height),12attitude_control(g2.attitude_control)13{ }1415void Mode::exit()16{17// call sub-classes exit18_exit();19}2021bool Mode::enter()22{23const bool ignore_checks = !hal.util->get_soft_armed(); // allow switching to any mode if disarmed. We rely on the arming check to perform24if (!ignore_checks) {2526// get EKF filter status27nav_filter_status filt_status;28rover.ahrs.get_filter_status(filt_status);2930// check position estimate. requires origin and at least one horizontal position flag to be true31const bool position_ok = rover.ekf_position_ok() && !rover.failsafe.ekf;32if (requires_position() && !position_ok) {33return false;34}3536// check velocity estimate (if we have position estimate, we must have velocity estimate)37if (requires_velocity() && !position_ok && !filt_status.flags.horiz_vel) {38return false;39}40}4142bool ret = _enter();4344// initialisation common to all modes45if (ret) {46// init reversed flag47init_reversed_flag();4849// clear sailboat tacking flags50g2.sailboat.clear_tack();51}5253return ret;54}5556// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments57// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise58// throttle_out is in the range -100 ~ +10059void Mode::get_pilot_input(float &steering_out, float &throttle_out) const60{61// no RC input means no throttle and centered steering62if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {63steering_out = 0;64throttle_out = 0;65return;66}6768// apply RC skid steer mixing69switch ((PilotSteerType)g.pilot_steer_type.get())70{71case PilotSteerType::DEFAULT:72case PilotSteerType::DIR_REVERSED_WHEN_REVERSING:73default: {74// by default regular and skid-steering vehicles reverse their rotation direction when backing up75throttle_out = rover.channel_throttle->get_control_in();76const float steering_dir = is_negative(throttle_out) ? -1 : 1;77steering_out = steering_dir * rover.channel_steer->get_control_in();78break;79}8081case PilotSteerType::TWO_PADDLES: {82// convert the two radio_in values from skid steering values83// left paddle from steering input channel, right paddle from throttle input channel84// steering = left-paddle - right-paddle85// throttle = average(left-paddle, right-paddle)86const float left_paddle = rover.channel_steer->norm_input_dz();87const float right_paddle = rover.channel_throttle->norm_input_dz();8889throttle_out = 0.5f * (left_paddle + right_paddle) * 100.0f;90steering_out = (left_paddle - right_paddle) * 0.5f * 4500.0f;91break;92}9394case PilotSteerType::DIR_UNCHANGED_WHEN_REVERSING: {95throttle_out = rover.channel_throttle->get_control_in();96steering_out = rover.channel_steer->get_control_in();97break;98}99}100}101102// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments103// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise104// throttle_out is in the range -100 ~ +100105void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &throttle_out) const106{107// do basic conversion108get_pilot_input(steering_out, throttle_out);109110// for skid steering vehicles, if pilot commands would lead to saturation111// we proportionally reduce steering and throttle112if (g2.motors.have_skid_steering()) {113const float steer_normalised = constrain_float(steering_out / 4500.0f, -1.0f, 1.0f);114const float throttle_normalised = constrain_float(throttle_out * 0.01f, -1.0f, 1.0f);115const float saturation_value = fabsf(steer_normalised) + fabsf(throttle_normalised);116if (saturation_value > 1.0f) {117steering_out /= saturation_value;118throttle_out /= saturation_value;119}120}121122// check for special case of input and output throttle being in opposite directions123float throttle_out_limited = g2.motors.get_slew_limited_throttle(throttle_out, rover.G_Dt);124if ((is_negative(throttle_out) != is_negative(throttle_out_limited)) &&125(g.pilot_steer_type == PilotSteerType::DEFAULT ||126g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) {127steering_out *= -1;128}129throttle_out = throttle_out_limited;130}131132// decode pilot steering and return steering_out and speed_out (in m/s)133void Mode::get_pilot_desired_steering_and_speed(float &steering_out, float &speed_out) const134{135float desired_throttle;136get_pilot_input(steering_out, desired_throttle);137speed_out = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);138// check for special case of input and output throttle being in opposite directions139float speed_out_limited = g2.attitude_control.get_desired_speed_accel_limited(speed_out, rover.G_Dt);140if ((is_negative(speed_out) != is_negative(speed_out_limited)) &&141(g.pilot_steer_type == PilotSteerType::DEFAULT ||142g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) {143steering_out *= -1;144}145speed_out = speed_out_limited;146}147148// decode pilot lateral movement input and return in lateral_out argument149void Mode::get_pilot_desired_lateral(float &lateral_out) const150{151// no RC input means no lateral input152if ((rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) || (rover.channel_lateral == nullptr)) {153lateral_out = 0;154return;155}156157// get pilot lateral input158lateral_out = rover.channel_lateral->get_control_in();159}160161// decode pilot's input and return heading_out (in cd) and speed_out (in m/s)162void Mode::get_pilot_desired_heading_and_speed(float &heading_out, float &speed_out) const163{164// get steering and throttle in the -1 to +1 range165float desired_steering = constrain_float(rover.channel_steer->norm_input_dz(), -1.0f, 1.0f);166float desired_throttle = constrain_float(rover.channel_throttle->norm_input_dz(), -1.0f, 1.0f);167168// handle two paddle input169if (g.pilot_steer_type == PilotSteerType::TWO_PADDLES) {170const float left_paddle = desired_steering;171const float right_paddle = desired_throttle;172desired_steering = (left_paddle - right_paddle) * 0.5f;173desired_throttle = (left_paddle + right_paddle) * 0.5f;174}175176// calculate angle of input stick vector177heading_out = wrap_360_cd(atan2f(desired_steering, desired_throttle) * DEGX100);178179// calculate throttle using magnitude of input stick vector180const float throttle = MIN(safe_sqrt(sq(desired_throttle) + sq(desired_steering)), 1.0f);181speed_out = throttle * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);182}183184// decode pilot roll and pitch inputs and return in roll_out and pitch_out arguments185// outputs are in the range -1 to +1186void Mode::get_pilot_desired_roll_and_pitch(float &roll_out, float &pitch_out) const187{188if (channel_roll != nullptr) {189roll_out = channel_roll->norm_input();190} else {191roll_out = 0.0f;192}193if (channel_pitch != nullptr) {194pitch_out = channel_pitch->norm_input();195} else {196pitch_out = 0.0f;197}198}199200// decode pilot walking_height inputs and return in walking_height_out arguments201// outputs are in the range -1 to +1202void Mode::get_pilot_desired_walking_height(float &walking_height_out) const203{204if (channel_walking_height != nullptr) {205walking_height_out = channel_walking_height->norm_input();206} else {207walking_height_out = 0.0f;208}209}210211// return heading (in degrees) to target destination (aka waypoint)212float Mode::wp_bearing() const213{214if (!is_autopilot_mode()) {215return 0.0f;216}217return g2.wp_nav.wp_bearing_cd() * 0.01f;218}219220// return short-term target heading in degrees (i.e. target heading back to line between waypoints)221float Mode::nav_bearing() const222{223if (!is_autopilot_mode()) {224return 0.0f;225}226return g2.wp_nav.nav_bearing_cd() * 0.01f;227}228229// return cross track error (i.e. vehicle's distance from the line between waypoints)230float Mode::crosstrack_error() const231{232if (!is_autopilot_mode()) {233return 0.0f;234}235return g2.wp_nav.crosstrack_error();236}237238// return desired lateral acceleration239float Mode::get_desired_lat_accel() const240{241if (!is_autopilot_mode()) {242return 0.0f;243}244return g2.wp_nav.get_lat_accel();245}246247// set desired location248bool Mode::set_desired_location(const Location &destination, Location next_destination )249{250if (!g2.wp_nav.set_desired_location(destination, next_destination)) {251return false;252}253254// initialise distance255_distance_to_destination = g2.wp_nav.get_distance_to_destination();256_reached_destination = false;257258return true;259}260261// get default speed for this mode (held in WP_SPEED or RTL_SPEED)262float Mode::get_speed_default(bool rtl) const263{264if (rtl && is_positive(g2.rtl_speed)) {265return g2.rtl_speed;266}267268return g2.wp_nav.get_default_speed();269}270271// execute the mission in reverse (i.e. backing up)272void Mode::set_reversed(bool value)273{274g2.wp_nav.set_reversed(value);275}276277// handle tacking request (from auxiliary switch) in sailboats278void Mode::handle_tack_request()279{280// autopilot modes handle tacking281if (is_autopilot_mode()) {282g2.sailboat.handle_tack_request_auto();283}284}285286void Mode::calc_throttle(float target_speed, bool avoidance_enabled)287{288// get acceleration limited target speed289target_speed = attitude_control.get_desired_speed_accel_limited(target_speed, rover.G_Dt);290291#if AP_AVOIDANCE_ENABLED292// apply object avoidance to desired speed using half vehicle's maximum deceleration293if (avoidance_enabled) {294g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw(), target_speed, rover.G_Dt);295if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {296// we are a sailboat trying to avoid fence, try a tack297if (rover.control_mode != &rover.mode_acro) {298rover.control_mode->handle_tack_request();299}300}301}302#endif // AP_AVOIDANCE_ENABLED303304// call throttle controller and convert output to -100 to +100 range305float throttle_out = 0.0f;306307if (g2.sailboat.sail_enabled()) {308// sailboats use special throttle and mainsail controller309g2.sailboat.get_throttle_and_set_mainsail(target_speed, throttle_out);310} else {311// call speed or stop controller312if (is_zero(target_speed) && !rover.is_balancebot()) {313bool stopped;314throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);315} else {316bool motor_lim_low = g2.motors.limit.throttle_lower || attitude_control.pitch_limited();317bool motor_lim_high = g2.motors.limit.throttle_upper || attitude_control.pitch_limited();318throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, motor_lim_low, motor_lim_high, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt);319}320321// if vehicle is balance bot, calculate actual throttle required for balancing322if (rover.is_balancebot()) {323rover.balancebot_pitch_control(throttle_out);324}325}326327// send to motor328g2.motors.set_throttle(throttle_out);329}330331// performs a controlled stop without turning332bool Mode::stop_vehicle()333{334// call throttle controller and convert output to -100 to +100 range335bool stopped = false;336float throttle_out;337338// if vehicle is balance bot, calculate throttle required for balancing339if (rover.is_balancebot()) {340throttle_out = 100.0f * attitude_control.get_throttle_out_speed(0, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt);341rover.balancebot_pitch_control(throttle_out);342} else {343throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);344}345346// relax sails if present347g2.sailboat.relax_sails();348349// send to motor350g2.motors.set_throttle(throttle_out);351352// do not turn while slowing down353float steering_out = 0.0;354if (!stopped) {355steering_out = attitude_control.get_steering_out_rate(0.0, g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt);356}357g2.motors.set_steering(steering_out * 4500.0);358359// return true once stopped360return stopped;361}362363// estimate maximum vehicle speed (in m/s)364// cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1365float Mode::calc_speed_max(float cruise_speed, float cruise_throttle) const366{367float speed_max;368369// sanity checks370if (cruise_throttle > 1.0f || cruise_throttle < 0.05f) {371speed_max = cruise_speed;372} else if (is_positive(g2.speed_max)) {373speed_max = g2.speed_max;374} else {375// project vehicle's maximum speed376speed_max = (1.0f / cruise_throttle) * cruise_speed;377}378379// constrain to 30m/s (108km/h) and return380return constrain_float(speed_max, 0.0f, 30.0f);381}382383// calculate pilot input to nudge speed up or down384// target_speed should be in meters/sec385// reversed should be true if the vehicle is intentionally backing up which allows the pilot to increase the backing up speed by pulling the throttle stick down386float Mode::calc_speed_nudge(float target_speed, bool reversed)387{388// sanity checks389if (g.throttle_cruise > 100 || g.throttle_cruise < 5) {390return target_speed;391}392393// convert pilot throttle input to speed394float pilot_steering, pilot_throttle;395get_pilot_input(pilot_steering, pilot_throttle);396float pilot_speed = pilot_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);397398// ignore pilot's input if in opposite direction to vehicle's desired direction of travel399// note that the target_speed may be negative while reversed is true (or vice-versa)400// while vehicle is transitioning between forward and backwards movement401if ((is_positive(pilot_speed) && reversed) ||402(is_negative(pilot_speed) && !reversed)) {403return target_speed;404}405406// return the larger of the pilot speed and the original target speed407if (reversed) {408return MIN(target_speed, pilot_speed);409} else {410return MAX(target_speed, pilot_speed);411}412}413414// high level call to navigate to waypoint415// uses wp_nav to calculate turn rate and speed to drive along the path from origin to destination416// this function updates _distance_to_destination417void Mode::navigate_to_waypoint()418{419// apply speed nudge from pilot420// calc_speed_nudge's "desired_speed" argument should be negative when vehicle is reversing421// AR_WPNav nudge_speed_max argu,ent should always be positive even when reversing422const float calc_nudge_input_speed = g2.wp_nav.get_speed_max() * (g2.wp_nav.get_reversed() ? -1.0 : 1.0);423const float nudge_speed_max = calc_speed_nudge(calc_nudge_input_speed, g2.wp_nav.get_reversed());424g2.wp_nav.set_nudge_speed_max(fabsf(nudge_speed_max));425426// update navigation controller427g2.wp_nav.update(rover.G_Dt);428_distance_to_destination = g2.wp_nav.get_distance_to_destination();429430#if AP_AVOIDANCE_ENABLED431// sailboats trigger tack if simple avoidance becomes active432if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {433// we are a sailboat trying to avoid fence, try a tack434rover.control_mode->handle_tack_request();435}436#endif437438// pass desired speed to throttle controller439// do not do simple avoidance because this is already handled in the position controller440calc_throttle(g2.wp_nav.get_speed(), false);441442float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd();443if (g2.sailboat.use_indirect_route(desired_heading_cd)) {444// sailboats use heading controller when tacking upwind445desired_heading_cd = g2.sailboat.calc_heading(desired_heading_cd);446// use pivot turn rate for tacks447const float turn_rate = g2.sailboat.tacking() ? g2.wp_nav.get_pivot_rate() : 0.0f;448calc_steering_to_heading(desired_heading_cd, turn_rate);449} else {450// retrieve turn rate from waypoint controller451float desired_turn_rate_rads = g2.wp_nav.get_turn_rate_rads();452453// if simple avoidance is active at very low speed do not attempt to turn454#if AP_AVOIDANCE_ENABLED455if (g2.avoid.limits_active() && (fabsf(attitude_control.get_desired_speed()) <= attitude_control.get_stop_speed())) {456desired_turn_rate_rads = 0.0f;457}458#endif459460// call turn rate steering controller461calc_steering_from_turn_rate(desired_turn_rate_rads);462}463}464465// calculate steering output given a turn rate466// desired turn rate in radians/sec. Positive to the right.467void Mode::calc_steering_from_turn_rate(float turn_rate)468{469// calculate and send final steering command to motor library470const float steering_out = attitude_control.get_steering_out_rate(turn_rate,471g2.motors.limit.steer_left,472g2.motors.limit.steer_right,473rover.G_Dt);474set_steering(steering_out * 4500.0f);475}476477/*478calculate steering output given lateral_acceleration479*/480void Mode::calc_steering_from_lateral_acceleration(float lat_accel, bool reversed)481{482// constrain to max G force483lat_accel = constrain_float(lat_accel, -attitude_control.get_turn_lat_accel_max(), attitude_control.get_turn_lat_accel_max());484485// send final steering command to motor library486const float steering_out = attitude_control.get_steering_out_lat_accel(lat_accel,487g2.motors.limit.steer_left,488g2.motors.limit.steer_right,489rover.G_Dt);490set_steering(steering_out * 4500.0f);491}492493// calculate steering output to drive towards desired heading494// rate_max is a maximum turn rate in deg/s. set to zero to use default turn rate limits495void Mode::calc_steering_to_heading(float desired_heading_cd, float rate_max_degs)496{497// call heading controller498const float steering_out = attitude_control.get_steering_out_heading(radians(desired_heading_cd*0.01f),499radians(rate_max_degs),500g2.motors.limit.steer_left,501g2.motors.limit.steer_right,502rover.G_Dt);503set_steering(steering_out * 4500.0f);504}505506void Mode::set_steering(float steering_value)507{508if (allows_stick_mixing() && g2.stick_mixing > 0) {509steering_value = channel_steer->stick_mixing((int16_t)steering_value);510}511g2.motors.set_steering(steering_value);512}513514Mode *Rover::mode_from_mode_num(const enum Mode::Number num)515{516Mode *ret = nullptr;517switch (num) {518case Mode::Number::MANUAL:519ret = &mode_manual;520break;521case Mode::Number::ACRO:522ret = &mode_acro;523break;524case Mode::Number::STEERING:525ret = &mode_steering;526break;527case Mode::Number::HOLD:528ret = &mode_hold;529break;530case Mode::Number::LOITER:531ret = &mode_loiter;532break;533#if MODE_FOLLOW_ENABLED534case Mode::Number::FOLLOW:535ret = &mode_follow;536break;537#endif538case Mode::Number::SIMPLE:539ret = &mode_simple;540break;541case Mode::Number::CIRCLE:542ret = &g2.mode_circle;543break;544case Mode::Number::AUTO:545ret = &mode_auto;546break;547case Mode::Number::RTL:548ret = &mode_rtl;549break;550case Mode::Number::SMART_RTL:551ret = &mode_smartrtl;552break;553case Mode::Number::GUIDED:554ret = &mode_guided;555break;556case Mode::Number::INITIALISING:557ret = &mode_initializing;558break;559#if MODE_DOCK_ENABLED560case Mode::Number::DOCK:561ret = (Mode *)g2.mode_dock_ptr;562break;563#endif564default:565break;566}567return ret;568}569570571