123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446 |
- #include <AP_Math/AP_Math.h>
- #include <AP_HAL/AP_HAL.h>
- #include "AR_WPNav.h"
- extern const AP_HAL::HAL& hal;
- #define AR_WPNAV_TIMEOUT_MS 100
- #define AR_WPNAV_SPEED_DEFAULT 2.0f
- #define AR_WPNAV_RADIUS_DEFAULT 2.0f
- #define AR_WPNAV_OVERSHOOT_DEFAULT 2.0f
- #define AR_WPNAV_PIVOT_ANGLE_DEFAULT 60
- #define AR_WPNAV_PIVOT_RATE_DEFAULT 90
- const AP_Param::GroupInfo AR_WPNav::var_info[] = {
-
-
-
-
-
-
-
- AP_GROUPINFO("SPEED", 1, AR_WPNav, _speed_max, AR_WPNAV_SPEED_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("RADIUS", 2, AR_WPNav, _radius, AR_WPNAV_RADIUS_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("OVERSHOOT", 3, AR_WPNav, _overshoot, AR_WPNAV_OVERSHOOT_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("PIVOT_ANGLE", 4, AR_WPNav, _pivot_angle, AR_WPNAV_PIVOT_ANGLE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("PIVOT_RATE", 5, AR_WPNav, _pivot_rate, AR_WPNAV_PIVOT_RATE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("SPEED_MIN", 6, AR_WPNav, _speed_min, 0),
- AP_GROUPEND
- };
- AR_WPNav::AR_WPNav(AR_AttitudeControl& atc, AP_Navigation& nav_controller) :
- _atc(atc),
- _nav_controller(nav_controller)
- {
- AP_Param::setup_object_defaults(this, var_info);
- }
- void AR_WPNav::update(float dt)
- {
-
- Location current_loc;
- float speed;
- if (!hal.util->get_soft_armed() || !_orig_and_dest_valid || !AP::ahrs().get_position(current_loc) || !_atc.get_forward_speed(speed)) {
- _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt);
- _desired_turn_rate_rads = 0.0f;
- return;
- }
-
- if (!is_active()) {
- _desired_speed_limited = speed;
- }
- _last_update_ms = AP_HAL::millis();
-
- bool stop_vehicle = false;
- AP_OAPathPlanner *oa = AP_OAPathPlanner::get_singleton();
- if (oa != nullptr) {
- const AP_OAPathPlanner::OA_RetState oa_retstate = oa->mission_avoidance(current_loc, _origin, _destination, _oa_origin, _oa_destination);
- switch (oa_retstate) {
- case AP_OAPathPlanner::OA_NOT_REQUIRED:
- _oa_active = false;
- break;
- case AP_OAPathPlanner::OA_PROCESSING:
- case AP_OAPathPlanner::OA_ERROR:
-
- stop_vehicle = true;
- _oa_active = false;
- break;
- case AP_OAPathPlanner::OA_SUCCESS:
- _oa_active = true;
- break;
- }
- }
- if (!_oa_active) {
- _oa_origin = _origin;
- _oa_destination = _destination;
- }
- update_distance_and_bearing_to_destination();
-
- const bool near_wp = _distance_to_destination <= _radius;
- const bool past_wp = !_oa_active && current_loc.past_interval_finish_line(_origin, _destination);
- if (!_reached_destination && (near_wp || past_wp)) {
- _reached_destination = true;
- }
-
- if (stop_vehicle) {
-
- _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt);
- _desired_lat_accel = 0.0f;
- _desired_turn_rate_rads = 0.0f;
- return;
- }
-
- update_steering(current_loc, speed);
-
- update_desired_speed(dt);
- }
- bool AR_WPNav::set_desired_location(const struct Location& destination, float next_leg_bearing_cd)
- {
-
- if (is_active() && _orig_and_dest_valid && _reached_destination) {
- _origin = _destination;
- } else {
-
- if (!get_stopping_location(_origin)) {
- return false;
- }
- }
-
- _oa_origin = _origin;
- _oa_destination = _destination = destination;
- _orig_and_dest_valid = true;
- _reached_destination = false;
- update_distance_and_bearing_to_destination();
-
- _desired_speed_final = 0.0f;
- if (!is_equal(next_leg_bearing_cd, AR_WPNAV_HEADING_UNKNOWN)) {
- const float curr_leg_bearing_cd = _origin.get_bearing_to(_destination);
- const float turn_angle_cd = wrap_180_cd(next_leg_bearing_cd - curr_leg_bearing_cd);
- if (fabsf(turn_angle_cd) < 10.0f) {
-
-
- _desired_speed_final = _desired_speed;
- } else if (use_pivot_steering_at_next_WP(turn_angle_cd)) {
-
- _desired_speed_final = 0.0f;
- } else {
-
- const float radius_m = fabsf(_overshoot / (cosf(radians(turn_angle_cd * 0.01f)) - 1.0f));
- _desired_speed_final = MIN(_desired_speed, safe_sqrt(_turn_max_mss * radius_m));
-
- apply_speed_min(_desired_speed_final);
- }
- }
- return true;
- }
- bool AR_WPNav::set_desired_location_to_stopping_location()
- {
- Location stopping_loc;
- if (!get_stopping_location(stopping_loc)) {
- return false;
- }
- return set_desired_location(stopping_loc);
- }
- bool AR_WPNav::set_desired_location_NED(const Vector3f& destination, float next_leg_bearing_cd)
- {
-
- Location destination_ned;
- if (!AP::ahrs().get_origin(destination_ned)) {
- return false;
- }
-
- destination_ned.offset(destination.x, destination.y);
- return set_desired_location(destination_ned, next_leg_bearing_cd);
- }
- bool AR_WPNav::get_stopping_location(Location& stopping_loc)
- {
- Location current_loc;
- if (!AP::ahrs().get_position(current_loc)) {
- return false;
- }
-
- const Vector2f velocity = AP::ahrs().groundspeed_vector();
- const float speed = velocity.length();
-
- if (!is_positive(speed)) {
- stopping_loc = current_loc;
- return true;
- }
-
- const float stopping_dist = _atc.get_stopping_distance(speed);
-
- const Vector2f stopping_offset = velocity.normalized() * stopping_dist;
- stopping_loc = current_loc;
- stopping_loc.offset(stopping_offset.x, stopping_offset.y);
- return true;
- }
- bool AR_WPNav::use_pivot_steering_at_next_WP(float yaw_error_cd) const
- {
-
- if (!_pivot_possible || _pivot_angle <= 0) {
- return false;
- }
-
- if (fabsf(yaw_error_cd) * 0.01f > _pivot_angle) {
- return true;
- }
- return false;
- }
- bool AR_WPNav::use_pivot_steering(float yaw_error_cd)
- {
-
- if (!_pivot_possible || (_pivot_angle <= 0)) {
- _pivot_active = false;
- return false;
- }
-
- const float yaw_error = fabsf(yaw_error_cd) * 0.01f;
-
- if (yaw_error > _pivot_angle) {
- _pivot_active = true;
- return true;
- }
-
- if (yaw_error < 10.0f) {
- _pivot_active = false;
- return false;
- }
-
- return _pivot_active;
- }
- bool AR_WPNav::is_active() const
- {
- return ((AP_HAL::millis() - _last_update_ms) < AR_WPNAV_TIMEOUT_MS);
- }
- void AR_WPNav::update_distance_and_bearing_to_destination()
- {
-
- Location current_loc;
- if (!_orig_and_dest_valid || !AP::ahrs().get_position(current_loc)) {
- _distance_to_destination = 0.0f;
- _wp_bearing_cd = 0.0f;
-
- _oa_distance_to_destination = 0.0f;
- _oa_wp_bearing_cd = 0.0f;
- return;
- }
- _distance_to_destination = current_loc.get_distance(_destination);
- _wp_bearing_cd = current_loc.get_bearing_to(_destination);
-
- if (_oa_active) {
- _oa_distance_to_destination = current_loc.get_distance(_oa_destination);
- _oa_wp_bearing_cd = current_loc.get_bearing_to(_oa_destination);
- } else {
- _oa_distance_to_destination = _distance_to_destination;
- _oa_wp_bearing_cd = _wp_bearing_cd;
- }
- }
- void AR_WPNav::update_steering(const Location& current_loc, float current_speed)
- {
-
- float yaw_cd = _reversed ? wrap_360_cd(_oa_wp_bearing_cd + 18000) : _oa_wp_bearing_cd;
- float yaw_error_cd = wrap_180_cd(yaw_cd - AP::ahrs().yaw_sensor);
-
- if (use_pivot_steering(yaw_error_cd)) {
- _cross_track_error = 0.0f;
- _desired_heading_cd = yaw_cd;
- _desired_lat_accel = 0.0f;
- _desired_turn_rate_rads = _atc.get_turn_rate_from_heading(radians(yaw_cd * 0.01f), radians(_pivot_rate));
- } else {
-
- _nav_controller.set_reverse(_reversed);
- _nav_controller.update_waypoint(_reached_destination ? current_loc : _oa_origin, _oa_destination, _radius);
-
- _desired_lat_accel = constrain_float(_nav_controller.lateral_acceleration(), -_turn_max_mss, _turn_max_mss);
- _desired_heading_cd = wrap_360_cd(_nav_controller.nav_bearing_cd());
- if (_reversed) {
- _desired_lat_accel *= -1.0f;
- _desired_heading_cd = wrap_360_cd(_desired_heading_cd + 18000);
- }
- _cross_track_error = _nav_controller.crosstrack_error();
- _desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, current_speed);
- }
- }
- void AR_WPNav::update_desired_speed(float dt)
- {
-
- if (_pivot_active) {
-
- _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt);
- return;
- }
-
- float des_speed_lim = _atc.get_desired_speed_accel_limited(_reversed ? -_desired_speed : _desired_speed, dt);
-
-
- float ahrs_yaw_sensor = AP::ahrs().yaw_sensor;
- const float heading_cd = is_negative(des_speed_lim) ? wrap_180_cd(ahrs_yaw_sensor + 18000) : ahrs_yaw_sensor;
- const float wp_yaw_diff_cd = wrap_180_cd(_oa_wp_bearing_cd - heading_cd);
- const float turn_angle_rad = fabsf(radians(wp_yaw_diff_cd * 0.01f));
-
- const float line_yaw_diff = wrap_180_cd(_oa_origin.get_bearing_to(_oa_destination) - heading_cd);
- const float dist_from_line = fabsf(_cross_track_error);
- const bool heading_away = is_positive(line_yaw_diff) == is_positive(_cross_track_error);
- const float wp_overshoot_adj = heading_away ? -dist_from_line : dist_from_line;
-
- float radius_m = 999.0f;
- const float radius_calc_denom = fabsf(1.0f - cosf(turn_angle_rad));
- if (!is_zero(radius_calc_denom)) {
- radius_m = MAX(0.0f, _overshoot + wp_overshoot_adj) / radius_calc_denom;
- }
-
- const float overshoot_speed_max = safe_sqrt(_turn_max_mss * MAX(_turn_radius, radius_m));
- des_speed_lim = constrain_float(des_speed_lim, -overshoot_speed_max, overshoot_speed_max);
-
- apply_speed_min(des_speed_lim);
-
- if (is_positive(_oa_distance_to_destination) && is_positive(_atc.get_decel_max())) {
- const float dist_speed_max = safe_sqrt(2.0f * _oa_distance_to_destination * _atc.get_decel_max() + sq(_desired_speed_final));
- des_speed_lim = constrain_float(des_speed_lim, -dist_speed_max, dist_speed_max);
- }
- _desired_speed_limited = des_speed_lim;
- }
- void AR_WPNav::set_turn_params(float turn_max_g, float turn_radius, bool pivot_possible)
- {
- _turn_max_mss = turn_max_g * GRAVITY_MSS;
- _turn_radius = turn_radius;
- _pivot_possible = pivot_possible;
- }
- void AR_WPNav::set_default_overshoot(float overshoot)
- {
- _overshoot.set_default(overshoot);
- }
- void AR_WPNav::apply_speed_min(float &desired_speed)
- {
- if (!is_positive(_speed_min)) {
- return;
- }
- float speed_min = MIN(_speed_min, _speed_max);
-
- if (fabsf(desired_speed) < speed_min) {
- desired_speed = is_negative(desired_speed) ? -speed_min : speed_min;
- }
- }
|