2019-05-10 02:59:31 -03:00
# pragma once
# include <AP_Common/AP_Common.h>
# include <AP_Common/Location.h>
# include <AP_Param/AP_Param.h>
2022-02-28 21:19:06 -04:00
# include <AP_HAL/Semaphores.h>
2019-05-10 02:59:31 -03:00
# include "AP_OABendyRuler.h"
# include "AP_OADijkstra.h"
2019-06-29 02:51:55 -03:00
# include "AP_OADatabase.h"
2019-05-10 02:59:31 -03:00
/*
* This class provides path planning around fence , stay - out zones and moving obstacles
*/
class AP_OAPathPlanner {
public :
AP_OAPathPlanner ( ) ;
/* Do not allow copies */
2022-09-30 06:50:43 -03:00
CLASS_NO_COPY ( AP_OAPathPlanner ) ;
2019-05-10 02:59:31 -03:00
// get singleton instance
static AP_OAPathPlanner * get_singleton ( ) {
return _singleton ;
}
// perform any required initialisation
void init ( ) ;
/// returns true if all pre-takeoff checks have completed successfully
bool pre_arm_check ( char * failure_msg , uint8_t failure_msg_len ) const ;
2019-06-26 04:15:41 -03:00
// object avoidance processing return status enum
enum OA_RetState : uint8_t {
OA_NOT_REQUIRED = 0 , // object avoidance is not required
OA_PROCESSING , // still calculating alternative path
OA_ERROR , // error during calculation
OA_SUCCESS // success
} ;
2021-03-23 23:33:04 -03:00
// path planner responsible for a particular result
enum OAPathPlannerUsed : uint8_t {
None = 0 ,
BendyRulerHorizontal ,
BendyRulerVertical ,
Dijkstras
} ;
2019-05-10 02:59:31 -03:00
// provides an alternative target location if path planning around obstacles is required
2023-12-14 02:19:51 -04:00
// returns true and updates result_origin, result_destination and result_next_destination with an intermediate path
// 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)
2021-03-23 23:33:04 -03:00
// path_planner_used updated with which path planner produced the result
2019-06-26 04:15:41 -03:00
OA_RetState mission_avoidance ( const Location & current_loc ,
2019-05-10 02:59:31 -03:00
const Location & origin ,
const Location & destination ,
2023-12-14 02:19:51 -04:00
const Location & next_destination ,
2019-05-10 02:59:31 -03:00
Location & result_origin ,
2021-03-23 23:33:04 -03:00
Location & result_destination ,
2023-12-14 02:19:51 -04:00
Location & result_next_destination ,
bool & result_dest_to_next_dest_clear ,
2021-03-23 23:33:04 -03:00
OAPathPlannerUsed & path_planner_used ) WARN_IF_UNUSED ;
2019-05-10 02:59:31 -03:00
// enumerations for _TYPE parameter
enum OAPathPlanTypes {
OA_PATHPLAN_DISABLED = 0 ,
OA_PATHPLAN_BENDYRULER = 1 ,
2020-08-24 04:04:35 -03:00
OA_PATHPLAN_DIJKSTRA = 2 ,
OA_PATHPLAN_DJIKSTRA_BENDYRULER = 3 ,
2019-05-10 02:59:31 -03:00
} ;
2020-05-21 05:37:45 -03:00
// enumeration for _OPTION parameter
enum OARecoveryOptions {
OA_OPTION_DISABLED = 0 ,
OA_OPTION_WP_RESET = ( 1 < < 0 ) ,
2021-10-11 19:35:36 -03:00
OA_OPTION_LOG_DIJKSTRA_POINTS = ( 1 < < 1 ) ,
2023-12-18 03:26:40 -04:00
OA_OPTION_FAST_WAYPOINTS = ( 1 < < 2 ) ,
2020-05-21 05:37:45 -03:00
} ;
uint16_t get_options ( ) const { return _options ; }
2019-05-10 02:59:31 -03:00
static const struct AP_Param : : GroupInfo var_info [ ] ;
private :
// avoidance thread that continually updates the avoidance_result structure based on avoidance_request
void avoidance_thread ( ) ;
2019-06-29 02:51:55 -03:00
bool start_thread ( ) ;
2019-05-10 02:59:31 -03:00
2021-03-23 23:33:04 -03:00
// helper function to map OABendyType to OAPathPlannerUsed
OAPathPlannerUsed map_bendytype_to_pathplannerused ( AP_OABendyRuler : : OABendyType bendy_type ) ;
2019-05-10 02:59:31 -03:00
// an avoidance request from the navigation code
struct avoidance_info {
Location current_loc ;
Location origin ;
Location destination ;
2023-12-14 02:19:51 -04:00
Location next_destination ;
2019-05-10 02:59:31 -03:00
Vector2f ground_speed_vec ;
uint32_t request_time_ms ;
} avoidance_request , avoidance_request2 ;
// an avoidance result from the avoidance thread
struct {
Location destination ; // destination vehicle is trying to get to (also used to verify the result matches a recent request)
2023-12-14 02:19:51 -04:00
Location next_destination ; // next destination vehicle is trying to get to (also used to verify the result matches a recent request)
2019-05-10 02:59:31 -03:00
Location origin_new ; // intermediate origin. The start of line segment that vehicle should follow
Location destination_new ; // intermediate destination vehicle should move towards
2023-12-14 02:19:51 -04:00
Location next_destination_new ; // intermediate next destination vehicle should move towards
bool 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)
2019-05-10 02:59:31 -03:00
uint32_t result_time_ms ; // system time the result was calculated (used to verify the result is recent)
2021-03-23 23:33:04 -03:00
OAPathPlannerUsed path_planner_used ; // path planner that produced the result
2019-06-26 04:15:41 -03:00
OA_RetState ret_state ; // OA_SUCCESS if the vehicle should move along the path from origin_new to destination_new
2019-05-10 02:59:31 -03:00
} avoidance_result ;
// parameters
2020-05-21 05:37:45 -03:00
AP_Int8 _type ; // avoidance algorithm to be used
2019-05-10 02:59:31 -03:00
AP_Float _margin_max ; // object avoidance will ignore objects more than this many meters from vehicle
2020-05-21 05:37:45 -03:00
AP_Int16 _options ; // Bitmask for options while recovering from Object Avoidance
2020-06-13 06:37:40 -03:00
2019-05-10 02:59:31 -03:00
// internal variables used by front end
2020-01-18 17:57:21 -04:00
HAL_Semaphore _rsem ; // semaphore for multi-thread use of avoidance_request and avoidance_result
2019-05-10 02:59:31 -03:00
bool _thread_created ; // true once background thread has been created
AP_OABendyRuler * _oabendyruler ; // Bendy Ruler algorithm
AP_OADijkstra * _oadijkstra ; // Dijkstra's algorithm
2019-06-29 02:51:55 -03:00
AP_OADatabase _oadatabase ; // Database of dynamic objects to avoid
2023-12-18 01:39:38 -04:00
uint32_t avoidance_latest_ms ; // last time Dijkstra's or BendyRuler algorithms ran (in the avoidance thread)
uint32_t _last_update_ms ; // system time that mission_avoidance was called in main thread
uint32_t _activated_ms ; // system time that object avoidance was most recently activated (used to avoid timeout error on first run)
2019-05-10 02:59:31 -03:00
2020-08-24 04:04:35 -03:00
bool proximity_only = true ;
2019-05-10 02:59:31 -03:00
static AP_OAPathPlanner * _singleton ;
} ;
namespace AP {
AP_OAPathPlanner * ap_oapathplanner ( ) ;
} ;