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_guided.cpp
Views: 1798
#include "Rover.h"12bool ModeGuided::_enter()3{4// initialise submode to stop or loiter5if (rover.is_boat()) {6if (!start_loiter()) {7start_stop();8}9} else {10start_stop();11}1213// initialise waypoint navigation library14g2.wp_nav.init();1516send_notification = false;1718return true;19}2021void ModeGuided::update()22{23switch (_guided_mode) {24case SubMode::WP:25{26// check if we've reached the destination27if (!g2.wp_nav.reached_destination()) {28// update navigation controller29navigate_to_waypoint();30} else {31// send notification32if (send_notification) {33send_notification = false;34rover.gcs().send_mission_item_reached_message(0);35}3637// we have reached the destination so stay here38if (rover.is_boat()) {39if (!start_loiter()) {40stop_vehicle();41}42} else {43stop_vehicle();44}45// update distance to destination46_distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination());47}48break;49}5051case SubMode::HeadingAndSpeed:52{53// stop vehicle if target not updated within 3 seconds54if (have_attitude_target && (millis() - _des_att_time_ms) > 3000) {55gcs().send_text(MAV_SEVERITY_WARNING, "target not received last 3secs, stopping");56have_attitude_target = false;57}58if (have_attitude_target) {59// run steering and throttle controllers60calc_steering_to_heading(_desired_yaw_cd);61calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);62} else {63// we have reached the destination so stay here64if (rover.is_boat()) {65if (!start_loiter()) {66stop_vehicle();67}68} else {69stop_vehicle();70}71}72break;73}7475case SubMode::TurnRateAndSpeed:76{77// stop vehicle if target not updated within 3 seconds78if (have_attitude_target && (millis() - _des_att_time_ms) > 3000) {79gcs().send_text(MAV_SEVERITY_WARNING, "target not received last 3secs, stopping");80have_attitude_target = false;81}82if (have_attitude_target) {83// run steering and throttle controllers84float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds * 0.01f),85g2.motors.limit.steer_left,86g2.motors.limit.steer_right,87rover.G_Dt);88set_steering(steering_out * 4500.0f);89calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);90} else {91// we have reached the destination so stay here92if (rover.is_boat()) {93if (!start_loiter()) {94stop_vehicle();95}96} else {97stop_vehicle();98}99}100break;101}102103case SubMode::Loiter:104{105rover.mode_loiter.update();106break;107}108109case SubMode::SteeringAndThrottle:110{111// handle timeout112if (_have_strthr && (AP_HAL::millis() - _strthr_time_ms) > 3000) {113_have_strthr = false;114gcs().send_text(MAV_SEVERITY_WARNING, "target not received last 3secs, stopping");115}116if (_have_strthr) {117// pass latest steering and throttle directly to motors library118g2.motors.set_steering(_strthr_steering * 4500.0f, false);119g2.motors.set_throttle(_strthr_throttle * 100.0f);120} else {121// loiter or stop vehicle122if (rover.is_boat()) {123if (!start_loiter()) {124stop_vehicle();125}126} else {127stop_vehicle();128}129}130break;131}132133case SubMode::Stop:134stop_vehicle();135break;136137default:138gcs().send_text(MAV_SEVERITY_WARNING, "Unknown GUIDED mode");139break;140}141}142143// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)144float ModeGuided::wp_bearing() const145{146switch (_guided_mode) {147case SubMode::WP:148return g2.wp_nav.wp_bearing_cd() * 0.01f;149case SubMode::HeadingAndSpeed:150case SubMode::TurnRateAndSpeed:151return 0.0f;152case SubMode::Loiter:153return rover.mode_loiter.wp_bearing();154case SubMode::SteeringAndThrottle:155case SubMode::Stop:156return 0.0f;157}158159// we should never reach here but just in case, return 0160return 0.0f;161}162163float ModeGuided::nav_bearing() const164{165switch (_guided_mode) {166case SubMode::WP:167return g2.wp_nav.nav_bearing_cd() * 0.01f;168case SubMode::HeadingAndSpeed:169case SubMode::TurnRateAndSpeed:170return 0.0f;171case SubMode::Loiter:172return rover.mode_loiter.nav_bearing();173case SubMode::SteeringAndThrottle:174case SubMode::Stop:175return 0.0f;176}177178// we should never reach here but just in case, return 0179return 0.0f;180}181182float ModeGuided::crosstrack_error() const183{184switch (_guided_mode) {185case SubMode::WP:186return g2.wp_nav.crosstrack_error();187case SubMode::HeadingAndSpeed:188case SubMode::TurnRateAndSpeed:189return 0.0f;190case SubMode::Loiter:191return rover.mode_loiter.crosstrack_error();192case SubMode::SteeringAndThrottle:193case SubMode::Stop:194return 0.0f;195}196197// we should never reach here but just in case, return 0198return 0.0f;199}200201float ModeGuided::get_desired_lat_accel() const202{203switch (_guided_mode) {204case SubMode::WP:205return g2.wp_nav.get_lat_accel();206case SubMode::HeadingAndSpeed:207case SubMode::TurnRateAndSpeed:208return 0.0f;209case SubMode::Loiter:210return rover.mode_loiter.get_desired_lat_accel();211case SubMode::SteeringAndThrottle:212case SubMode::Stop:213return 0.0f;214}215216// we should never reach here but just in case, return 0217return 0.0f;218}219220// return distance (in meters) to destination221float ModeGuided::get_distance_to_destination() const222{223switch (_guided_mode) {224case SubMode::WP:225return _distance_to_destination;226case SubMode::HeadingAndSpeed:227case SubMode::TurnRateAndSpeed:228return 0.0f;229case SubMode::Loiter:230return rover.mode_loiter.get_distance_to_destination();231case SubMode::SteeringAndThrottle:232case SubMode::Stop:233return 0.0f;234}235236// we should never reach here but just in case, return 0237return 0.0f;238}239240// return true if vehicle has reached or even passed destination241bool ModeGuided::reached_destination() const242{243switch (_guided_mode) {244case SubMode::WP:245return g2.wp_nav.reached_destination();246case SubMode::HeadingAndSpeed:247case SubMode::TurnRateAndSpeed:248case SubMode::Loiter:249case SubMode::SteeringAndThrottle:250case SubMode::Stop:251return true;252}253254// we should never reach here but just in case, return true is the safer option255return true;256}257258// set desired speed in m/s259bool ModeGuided::set_desired_speed(float speed)260{261switch (_guided_mode) {262case SubMode::WP:263return g2.wp_nav.set_speed_max(speed);264case SubMode::HeadingAndSpeed:265case SubMode::TurnRateAndSpeed:266// speed is set from mavlink message267return false;268case SubMode::Loiter:269return rover.mode_loiter.set_desired_speed(speed);270case SubMode::SteeringAndThrottle:271case SubMode::Stop:272// no speed control273return false;274}275return false;276}277278// get desired location279bool ModeGuided::get_desired_location(Location& destination) const280{281switch (_guided_mode) {282case SubMode::WP:283if (g2.wp_nav.is_destination_valid()) {284destination = g2.wp_nav.get_oa_destination();285return true;286}287return false;288case SubMode::HeadingAndSpeed:289case SubMode::TurnRateAndSpeed:290// not supported in these submodes291return false;292case SubMode::Loiter:293// get destination from loiter294return rover.mode_loiter.get_desired_location(destination);295case SubMode::SteeringAndThrottle:296case SubMode::Stop:297// no desired location in this submode298break;299}300301// should never get here but just in case302return false;303}304305// set desired location306bool ModeGuided::set_desired_location(const Location &destination, Location next_destination)307{308if (use_scurves_for_navigation()) {309// use scurves for navigation310if (!g2.wp_nav.set_desired_location(destination, next_destination)) {311return false;312}313} else {314// use position controller input shaping for navigation315// this does not support object avoidance but does allow faster updates of the target316if (!g2.wp_nav.set_desired_location_expect_fast_update(destination)) {317return false;318}319}320321// handle guided specific initialisation and logging322_guided_mode = SubMode::WP;323send_notification = true;324#if HAL_LOGGING_ENABLED325rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f));326#endif327return true;328}329330// set desired attitude331void ModeGuided::set_desired_heading_and_speed(float yaw_angle_cd, float target_speed)332{333// initialisation and logging334_guided_mode = SubMode::HeadingAndSpeed;335_des_att_time_ms = AP_HAL::millis();336337// record targets338_desired_yaw_cd = yaw_angle_cd;339_desired_speed = target_speed;340have_attitude_target = true;341342#if HAL_LOGGING_ENABLED343// log new target344rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_cd, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f));345#endif346}347348void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed)349{350// handle initialisation351if (_guided_mode != SubMode::HeadingAndSpeed) {352_guided_mode = SubMode::HeadingAndSpeed;353_desired_yaw_cd = ahrs.yaw_sensor;354}355set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd + yaw_delta_cd), target_speed);356}357358// set desired velocity359void ModeGuided::set_desired_turn_rate_and_speed(float turn_rate_cds, float target_speed)360{361// handle initialisation362_guided_mode = SubMode::TurnRateAndSpeed;363_des_att_time_ms = AP_HAL::millis();364365// record targets366_desired_yaw_rate_cds = turn_rate_cds;367_desired_speed = target_speed;368have_attitude_target = true;369370#if HAL_LOGGING_ENABLED371// log new target372rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_rate_cds, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f));373#endif374}375376// set steering and throttle (both in the range -1 to +1)377void ModeGuided::set_steering_and_throttle(float steering, float throttle)378{379_guided_mode = SubMode::SteeringAndThrottle;380_strthr_time_ms = AP_HAL::millis();381_strthr_steering = constrain_float(steering, -1.0f, 1.0f);382_strthr_throttle = constrain_float(throttle, -1.0f, 1.0f);383_have_strthr = true;384}385386bool ModeGuided::start_loiter()387{388if (rover.mode_loiter.enter()) {389_guided_mode = SubMode::Loiter;390return true;391}392return false;393}394395396// start stopping vehicle as quickly as possible397void ModeGuided::start_stop()398{399_guided_mode = SubMode::Stop;400}401402// set guided timeout and movement limits403void ModeGuided::limit_set(uint32_t timeout_ms, float horiz_max)404{405limit.timeout_ms = timeout_ms;406limit.horiz_max = horiz_max;407}408409// clear/turn off guided limits410void ModeGuided::limit_clear()411{412limit.timeout_ms = 0;413limit.horiz_max = 0.0f;414}415416// initialise guided start time and location as reference for limit checking417// only called from AUTO mode's start_guided method418void ModeGuided::limit_init_time_and_location()419{420limit.start_time_ms = AP_HAL::millis();421limit.start_loc = rover.current_loc;422}423424// returns true if guided mode has breached a limit425bool ModeGuided::limit_breached() const426{427// check if we have passed the timeout428if ((limit.timeout_ms > 0) && (millis() - limit.start_time_ms >= limit.timeout_ms)) {429return true;430}431432// check if we have gone beyond horizontal limit433if (is_positive(limit.horiz_max)) {434return (rover.current_loc.get_distance(limit.start_loc) > limit.horiz_max);435}436437// if we got this far we must be within limits438return false;439}440441// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping442// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping)443bool ModeGuided::use_scurves_for_navigation() const444{445return ((g2.guided_options.get() & uint32_t(Options::SCurvesUsedForNavigation)) != 0);446}447448449