Path: blob/master/libraries/AC_Avoidance/AP_OAPathPlanner.cpp
4182 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AC_Avoidance_config.h"1617#if AP_OAPATHPLANNER_ENABLED1819#include "AP_OAPathPlanner.h"20#include <AP_Math/AP_Math.h>21#include <AP_AHRS/AP_AHRS.h>22#include <AC_Fence/AC_Fence.h>23#include <AP_Logger/AP_Logger.h>24#include "AP_OABendyRuler.h"25#include "AP_OADijkstra.h"2627extern const AP_HAL::HAL &hal;2829// parameter defaults30static constexpr float OA_MARGIN_MAX_DEFAULT = 5;31static constexpr int16_t OA_OPTIONS_DEFAULT = 1;3233static constexpr int16_t OA_UPDATE_MS = 1000; // path planning updates run at 1hz34static constexpr int16_t OA_TIMEOUT_MS = 3000; // results over 3 seconds old are ignored3536const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = {3738// @Param: TYPE39// @DisplayName: Object Avoidance Path Planning algorithm to use40// @Description: Enabled/disable path planning around obstacles41// @Values: 0:Disabled,1:BendyRuler,2:Dijkstra,3:Dijkstra with BendyRuler42// @User: Standard43AP_GROUPINFO_FLAGS("TYPE", 1, AP_OAPathPlanner, _type, OA_PATHPLAN_DISABLED, AP_PARAM_FLAG_ENABLE),4445// Note: Do not use Index "2" for any new parameter46// It was being used by _LOOKAHEAD which was later moved to AP_OABendyRuler4748// @Param: MARGIN_MAX49// @DisplayName: Object Avoidance wide margin distance50// @Description: Object Avoidance will ignore objects more than this many meters from vehicle51// @Units: m52// @Range: 0.1 10053// @Increment: 154// @User: Standard55AP_GROUPINFO("MARGIN_MAX", 3, AP_OAPathPlanner, _margin_max, OA_MARGIN_MAX_DEFAULT),5657// @Group: DB_58// @Path: AP_OADatabase.cpp59AP_SUBGROUPINFO(_oadatabase, "DB_", 4, AP_OAPathPlanner, AP_OADatabase),6061// @Param: OPTIONS62// @DisplayName: Options while recovering from Object Avoidance63// @Description: Bitmask which will govern vehicles behaviour while recovering from Obstacle Avoidance (i.e Avoidance is turned off after the path ahead is clear).64// @Bitmask{Rover}: 0: Reset the origin of the waypoint to the present location, 1: log Dijkstra points65// @Bitmask{Copter}: 1:log Dijkstra points, 2:Allow fast waypoints (Dijkastras only)66// @User: Standard67AP_GROUPINFO("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT),6869// @Group: BR_70// @Path: AP_OABendyRuler.cpp71AP_SUBGROUPPTR(_oabendyruler, "BR_", 6, AP_OAPathPlanner, AP_OABendyRuler),7273AP_GROUPEND74};7576/// Constructor77AP_OAPathPlanner::AP_OAPathPlanner()78{79_singleton = this;8081AP_Param::setup_object_defaults(this, var_info);82}8384// perform any required initialisation85void AP_OAPathPlanner::init()86{87// run background task looking for best alternative destination88switch (_type) {89case OA_PATHPLAN_DISABLED:90// do nothing91return;92case OA_PATHPLAN_BENDYRULER:93if (_oabendyruler == nullptr) {94_oabendyruler = NEW_NOTHROW AP_OABendyRuler();95AP_Param::load_object_from_eeprom(_oabendyruler, AP_OABendyRuler::var_info);96}97break;98case OA_PATHPLAN_DIJKSTRA:99#if AP_FENCE_ENABLED100if (_oadijkstra == nullptr) {101_oadijkstra = NEW_NOTHROW AP_OADijkstra(_options);102}103#endif104break;105case OA_PATHPLAN_DJIKSTRA_BENDYRULER:106#if AP_FENCE_ENABLED107if (_oadijkstra == nullptr) {108_oadijkstra = NEW_NOTHROW AP_OADijkstra(_options);109}110#endif111if (_oabendyruler == nullptr) {112_oabendyruler = NEW_NOTHROW AP_OABendyRuler();113AP_Param::load_object_from_eeprom(_oabendyruler, AP_OABendyRuler::var_info);114}115break;116}117118_oadatabase.init();119start_thread();120}121122// pre-arm checks that algorithms have been initialised successfully123bool AP_OAPathPlanner::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const124{125// check if initialisation has succeeded126switch (_type) {127case OA_PATHPLAN_DISABLED:128// do nothing129break;130case OA_PATHPLAN_BENDYRULER:131if (_oabendyruler == nullptr) {132hal.util->snprintf(failure_msg, failure_msg_len, "BendyRuler OA requires reboot");133return false;134}135break;136case OA_PATHPLAN_DIJKSTRA:137if (_oadijkstra == nullptr) {138hal.util->snprintf(failure_msg, failure_msg_len, "Dijkstra OA requires reboot");139return false;140}141break;142case OA_PATHPLAN_DJIKSTRA_BENDYRULER:143if(_oadijkstra == nullptr || _oabendyruler == nullptr) {144hal.util->snprintf(failure_msg, failure_msg_len, "OA requires reboot");145return false;146}147break;148}149return true;150}151152bool AP_OAPathPlanner::start_thread()153{154WITH_SEMAPHORE(_rsem);155156if (_thread_created) {157return true;158}159if (_type == OA_PATHPLAN_DISABLED) {160return false;161}162163// create the avoidance thread as low priority. It should soak164// up spare CPU cycles to fill in the avoidance_result structure based165// on requests in avoidance_request166if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_OAPathPlanner::avoidance_thread, void),167"avoidance",1688192, AP_HAL::Scheduler::PRIORITY_IO, -1)) {169return false;170}171_thread_created = true;172return true;173}174175// helper function to map OABendyType to OAPathPlannerUsed176AP_OAPathPlanner::OAPathPlannerUsed AP_OAPathPlanner::map_bendytype_to_pathplannerused(AP_OABendyRuler::OABendyType bendy_type)177{178switch (bendy_type) {179case AP_OABendyRuler::OABendyType::OA_BENDY_HORIZONTAL:180return OAPathPlannerUsed::BendyRulerHorizontal;181182case AP_OABendyRuler::OABendyType::OA_BENDY_VERTICAL:183return OAPathPlannerUsed::BendyRulerVertical;184185default:186case AP_OABendyRuler::OABendyType::OA_BENDY_DISABLED:187return OAPathPlannerUsed::None;188}189}190191// provides an alternative target location if path planning around obstacles is required192// returns true and updates result_origin, result_destination, result_next_destination with an intermediate path193// result_dest_to_next_dest_clear is set to true if the path from result_destination to result_next_destination is clear (only supported by Dijkstras)194// path_planner_used updated with which path planner produced the result195AP_OAPathPlanner::OA_RetState AP_OAPathPlanner::mission_avoidance(const Location ¤t_loc,196const Location &origin,197const Location &destination,198const Location &next_destination,199Location &result_origin,200Location &result_destination,201Location &result_next_destination,202bool &result_dest_to_next_dest_clear,203OAPathPlannerUsed &path_planner_used)204{205// exit immediately if disabled or thread is not running from a failed init206if (_type == OA_PATHPLAN_DISABLED || !_thread_created) {207return OA_NOT_REQUIRED;208}209210// check if just activated to avoid initial timeout error211const uint32_t now = AP_HAL::millis();212if (now - _last_update_ms > 200) {213_activated_ms = now;214}215_last_update_ms = now;216217WITH_SEMAPHORE(_rsem);218219// place new request for the thread to work on220avoidance_request.current_loc = current_loc;221avoidance_request.origin = origin;222avoidance_request.destination = destination;223avoidance_request.next_destination = next_destination;224avoidance_request.ground_speed_vec = AP::ahrs().groundspeed_vector();225avoidance_request.request_time_ms = now;226227// check result's destination and next_destination matches our request228// e.g. check this result was using our current inputs and not from an old request229const bool destination_matches = destination.same_latlon_as(avoidance_result.destination);230const bool next_destination_matches = next_destination.same_latlon_as(avoidance_result.next_destination);231232// check results have not timed out233const bool timed_out = (now - avoidance_result.result_time_ms > OA_TIMEOUT_MS) && (now - _activated_ms > OA_TIMEOUT_MS);234235// return results from background thread's latest checks236if (destination_matches && next_destination_matches && !timed_out) {237// we have a result from the thread238result_origin = avoidance_result.origin_new;239result_destination = avoidance_result.destination_new;240result_next_destination = avoidance_result.next_destination_new;241result_dest_to_next_dest_clear = avoidance_result.dest_to_next_dest_clear;242path_planner_used = avoidance_result.path_planner_used;243return avoidance_result.ret_state;244}245246// if timeout then path planner is taking too long to respond247if (timed_out) {248return OA_ERROR;249}250251// background thread is working on a new destination252return OA_PROCESSING;253}254255// avoidance thread that continually updates the avoidance_result structure based on avoidance_request256void AP_OAPathPlanner::avoidance_thread()257{258// require ekf origin to have been set259bool origin_set = false;260while (!origin_set) {261hal.scheduler->delay(500);262Location ekf_origin {};263{264WITH_SEMAPHORE(AP::ahrs().get_semaphore());265origin_set = AP::ahrs().get_origin(ekf_origin);266}267}268269while (true) {270271// if database queue needs attention, service it faster272if (_oadatabase.process_queue()) {273hal.scheduler->delay(1);274} else {275hal.scheduler->delay(20);276}277278const uint32_t now = AP_HAL::millis();279if (now - avoidance_latest_ms < OA_UPDATE_MS) {280continue;281}282avoidance_latest_ms = now;283284_oadatabase.update();285286// values returned by path planners287Location origin_new;288Location destination_new;289Location next_destination_new;290bool dest_to_next_dest_clear = false;291{292WITH_SEMAPHORE(_rsem);293if (now - avoidance_request.request_time_ms > OA_TIMEOUT_MS) {294// this is a very old request, don't process it295continue;296}297298// copy request to avoid conflict with main thread299avoidance_request2 = avoidance_request;300301// store passed in origin, destination and next_destination so we can return it if object avoidance is not required302origin_new = avoidance_request.origin;303destination_new = avoidance_request.destination;304next_destination_new = avoidance_request.next_destination;305}306307// run background task looking for best alternative destination308OA_RetState res = OA_NOT_REQUIRED;309OAPathPlannerUsed path_planner_used = OAPathPlannerUsed::None;310switch (_type) {311case OA_PATHPLAN_DISABLED:312continue;313case OA_PATHPLAN_BENDYRULER: {314if (_oabendyruler == nullptr) {315continue;316}317_oabendyruler->set_config(_margin_max);318319AP_OABendyRuler::OABendyType bendy_type;320if (_oabendyruler->update(avoidance_request2.current_loc, avoidance_request2.destination, avoidance_request2.ground_speed_vec, origin_new, destination_new, bendy_type, false)) {321res = OA_SUCCESS;322}323path_planner_used = map_bendytype_to_pathplannerused(bendy_type);324break;325}326327case OA_PATHPLAN_DIJKSTRA: {328#if AP_FENCE_ENABLED329if (_oadijkstra == nullptr) {330continue;331}332_oadijkstra->set_fence_margin(_margin_max);333const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc,334avoidance_request2.destination,335avoidance_request2.next_destination,336origin_new,337destination_new,338next_destination_new,339dest_to_next_dest_clear);340switch (dijkstra_state) {341case AP_OADijkstra::DIJKSTRA_STATE_NOT_REQUIRED:342res = OA_NOT_REQUIRED;343break;344case AP_OADijkstra::DIJKSTRA_STATE_ERROR:345res = OA_ERROR;346break;347case AP_OADijkstra::DIJKSTRA_STATE_SUCCESS:348res = OA_SUCCESS;349break;350}351path_planner_used = OAPathPlannerUsed::Dijkstras;352#endif353break;354}355356case OA_PATHPLAN_DJIKSTRA_BENDYRULER: {357if ((_oabendyruler == nullptr) || _oadijkstra == nullptr) {358continue;359}360_oabendyruler->set_config(_margin_max);361AP_OABendyRuler::OABendyType bendy_type;362if (_oabendyruler->update(avoidance_request2.current_loc, avoidance_request2.destination, avoidance_request2.ground_speed_vec, origin_new, destination_new, bendy_type, proximity_only)) {363// detected a obstacle by vehicle's proximity sensor. Switch avoidance to BendyRuler till obstacle is out of the way364proximity_only = false;365res = OA_SUCCESS;366path_planner_used = map_bendytype_to_pathplannerused(bendy_type);367break;368} else {369// cleared all obstacles, trigger Dijkstra's to calculate path based on current deviated position370#if AP_FENCE_ENABLED371if (proximity_only == false) {372_oadijkstra->recalculate_path();373}374#endif375// only use proximity avoidance now for BendyRuler376proximity_only = true;377}378#if AP_FENCE_ENABLED379_oadijkstra->set_fence_margin(_margin_max);380const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc,381avoidance_request2.destination,382avoidance_request2.next_destination,383origin_new,384destination_new,385next_destination_new,386dest_to_next_dest_clear);387switch (dijkstra_state) {388case AP_OADijkstra::DIJKSTRA_STATE_NOT_REQUIRED:389res = OA_NOT_REQUIRED;390break;391case AP_OADijkstra::DIJKSTRA_STATE_ERROR:392res = OA_ERROR;393break;394case AP_OADijkstra::DIJKSTRA_STATE_SUCCESS:395res = OA_SUCCESS;396break;397}398path_planner_used = OAPathPlannerUsed::Dijkstras;399#endif400break;401}402403} // switch404405{406// give the main thread the avoidance result407WITH_SEMAPHORE(_rsem);408409// place the destination and next destination used into the result (used by the caller to verify the result matches their request)410avoidance_result.destination = avoidance_request2.destination;411avoidance_result.next_destination = avoidance_request2.next_destination;412avoidance_result.dest_to_next_dest_clear = dest_to_next_dest_clear;413414// fill the result structure with the intermediate path415avoidance_result.origin_new = (res == OA_SUCCESS) ? origin_new : avoidance_result.origin_new;416avoidance_result.destination_new = (res == OA_SUCCESS) ? destination_new : avoidance_result.destination;417avoidance_result.next_destination_new = (res == OA_SUCCESS) ? next_destination_new : avoidance_result.next_destination;418419// create new avoidance result.dest_to_next_dest_clear field. fill in with results from dijkstras or leave as unknown420avoidance_result.result_time_ms = AP_HAL::millis();421avoidance_result.path_planner_used = path_planner_used;422avoidance_result.ret_state = res;423}424}425}426427// singleton instance428AP_OAPathPlanner *AP_OAPathPlanner::_singleton;429430namespace AP {431432AP_OAPathPlanner *ap_oapathplanner()433{434return AP_OAPathPlanner::get_singleton();435}436437}438439#endif // AP_OAPATHPLANNER_ENABLED440441442