Path: blob/master/libraries/AC_Avoidance/AP_OAPathPlanner.h
4182 views
#pragma once12#include "AC_Avoidance_config.h"34#if AP_OAPATHPLANNER_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_Common/Location.h>8#include <AP_Param/AP_Param.h>9#include <AP_HAL/Semaphores.h>1011#include "AP_OABendyRuler.h"12#include "AP_OADijkstra.h"13#include "AP_OADatabase.h"1415/*16* This class provides path planning around fence, stay-out zones and moving obstacles17*/18class AP_OAPathPlanner {1920public:21AP_OAPathPlanner();2223/* Do not allow copies */24CLASS_NO_COPY(AP_OAPathPlanner);2526// get singleton instance27static AP_OAPathPlanner *get_singleton() {28return _singleton;29}3031// perform any required initialisation32void init();3334/// returns true if all pre-takeoff checks have completed successfully35bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;3637// object avoidance processing return status enum38enum OA_RetState : uint8_t {39OA_NOT_REQUIRED = 0, // object avoidance is not required40OA_PROCESSING, // still calculating alternative path41OA_ERROR, // error during calculation42OA_SUCCESS // success43};4445// path planner responsible for a particular result46enum OAPathPlannerUsed : uint8_t {47None = 0,48BendyRulerHorizontal,49BendyRulerVertical,50Dijkstras51};5253// provides an alternative target location if path planning around obstacles is required54// returns true and updates result_origin, result_destination and result_next_destination with an intermediate path55// 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)56// path_planner_used updated with which path planner produced the result57OA_RetState mission_avoidance(const Location ¤t_loc,58const Location &origin,59const Location &destination,60const Location &next_destination,61Location &result_origin,62Location &result_destination,63Location &result_next_destination,64bool &result_dest_to_next_dest_clear,65OAPathPlannerUsed &path_planner_used) WARN_IF_UNUSED;6667// enumerations for _TYPE parameter68enum OAPathPlanTypes {69OA_PATHPLAN_DISABLED = 0,70OA_PATHPLAN_BENDYRULER = 1,71OA_PATHPLAN_DIJKSTRA = 2,72OA_PATHPLAN_DJIKSTRA_BENDYRULER = 3,73};7475// enumeration for _OPTION parameter76enum OARecoveryOptions {77OA_OPTION_DISABLED = 0,78OA_OPTION_WP_RESET = (1 << 0),79OA_OPTION_LOG_DIJKSTRA_POINTS = (1 << 1),80OA_OPTION_FAST_WAYPOINTS = (1 << 2),81};8283uint16_t get_options() const { return _options;}8485static const struct AP_Param::GroupInfo var_info[];8687private:8889// avoidance thread that continually updates the avoidance_result structure based on avoidance_request90void avoidance_thread();91bool start_thread();9293// helper function to map OABendyType to OAPathPlannerUsed94OAPathPlannerUsed map_bendytype_to_pathplannerused(AP_OABendyRuler::OABendyType bendy_type);9596// an avoidance request from the navigation code97struct avoidance_info {98Location current_loc;99Location origin;100Location destination;101Location next_destination;102Vector2f ground_speed_vec;103uint32_t request_time_ms;104} avoidance_request, avoidance_request2;105106// an avoidance result from the avoidance thread107struct {108Location destination; // destination vehicle is trying to get to (also used to verify the result matches a recent request)109Location next_destination; // next destination vehicle is trying to get to (also used to verify the result matches a recent request)110Location origin_new; // intermediate origin. The start of line segment that vehicle should follow111Location destination_new; // intermediate destination vehicle should move towards112Location next_destination_new; // intermediate next destination vehicle should move towards113bool dest_to_next_dest_clear; // true if the path from destination_new to next_destination_new is clear and does not require path planning (only supported by Dijkstras)114uint32_t result_time_ms; // system time the result was calculated (used to verify the result is recent)115OAPathPlannerUsed path_planner_used; // path planner that produced the result116OA_RetState ret_state; // OA_SUCCESS if the vehicle should move along the path from origin_new to destination_new117} avoidance_result;118119// parameters120AP_Int8 _type; // avoidance algorithm to be used121AP_Float _margin_max; // object avoidance will ignore objects more than this many meters from vehicle122AP_Int16 _options; // Bitmask for options while recovering from Object Avoidance123124// internal variables used by front end125HAL_Semaphore _rsem; // semaphore for multi-thread use of avoidance_request and avoidance_result126bool _thread_created; // true once background thread has been created127AP_OABendyRuler *_oabendyruler; // Bendy Ruler algorithm128AP_OADijkstra *_oadijkstra; // Dijkstra's algorithm129AP_OADatabase _oadatabase; // Database of dynamic objects to avoid130uint32_t avoidance_latest_ms; // last time Dijkstra's or BendyRuler algorithms ran (in the avoidance thread)131uint32_t _last_update_ms; // system time that mission_avoidance was called in main thread132uint32_t _activated_ms; // system time that object avoidance was most recently activated (used to avoid timeout error on first run)133134bool proximity_only = true;135static AP_OAPathPlanner *_singleton;136};137138namespace AP {139AP_OAPathPlanner *ap_oapathplanner();140};141142#endif // AP_OAPATHPLANNER_ENABLED143144145