2019-05-10 02:59:31 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
# include "AP_OAPathPlanner.h"
# include <AP_Math/AP_Math.h>
# include <AP_AHRS/AP_AHRS.h>
# include <AC_Fence/AC_Fence.h>
# include <AP_Logger/AP_Logger.h>
# include "AP_OABendyRuler.h"
# include "AP_OADijkstra.h"
extern const AP_HAL : : HAL & hal ;
// parameter defaults
2019-08-09 01:44:30 -03:00
const float OA_MARGIN_MAX_DEFAULT = 5 ;
2020-11-08 02:24:34 -04:00
const int16_t OA_OPTIONS_DEFAULT = 1 ;
2019-05-10 02:59:31 -03:00
2019-12-09 07:07:31 -04:00
const int16_t OA_UPDATE_MS = 1000 ; // path planning updates run at 1hz
const int16_t OA_TIMEOUT_MS = 3000 ; // results over 3 seconds old are ignored
2019-05-10 02:59:31 -03:00
const AP_Param : : GroupInfo AP_OAPathPlanner : : var_info [ ] = {
// @Param: TYPE
// @DisplayName: Object Avoidance Path Planning algorithm to use
// @Description: Enabled/disable path planning around obstacles
2020-08-24 04:04:35 -03:00
// @Values: 0:Disabled,1:BendyRuler,2:Dijkstra,3:Dijkstra with BendyRuler
2019-05-10 02:59:31 -03:00
// @User: Standard
AP_GROUPINFO_FLAGS ( " TYPE " , 1 , AP_OAPathPlanner , _type , OA_PATHPLAN_DISABLED , AP_PARAM_FLAG_ENABLE ) ,
2020-06-13 06:37:40 -03:00
// Note: Do not use Index "2" for any new parameter
// It was being used by _LOOKAHEAD which was later moved to AP_OABendyRuler
2019-05-10 02:59:31 -03:00
// @Param: MARGIN_MAX
// @DisplayName: Object Avoidance wide margin distance
// @Description: Object Avoidance will ignore objects more than this many meters from vehicle
// @Units: m
2019-06-29 02:51:55 -03:00
// @Range: 0.1 100
2019-05-10 02:59:31 -03:00
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " MARGIN_MAX " , 3 , AP_OAPathPlanner , _margin_max , OA_MARGIN_MAX_DEFAULT ) ,
2019-06-29 02:51:55 -03:00
// @Group: DB_
// @Path: AP_OADatabase.cpp
AP_SUBGROUPINFO ( _oadatabase , " DB_ " , 4 , AP_OAPathPlanner , AP_OADatabase ) ,
2020-11-08 02:24:34 -04:00
// @Param{Rover}: OPTIONS
2020-05-21 05:37:45 -03:00
// @DisplayName: Options while recovering from Object Avoidance
// @Description: Bitmask which will govern vehicles behaviour while recovering from Obstacle Avoidance (i.e Avoidance is turned off after the path ahead is clear).
// @Bitmask: 0: Reset the origin of the waypoint to the present location
// @User: Standard
2020-11-08 02:24:34 -04:00
AP_GROUPINFO_FRAME ( " OPTIONS " , 5 , AP_OAPathPlanner , _options , OA_OPTIONS_DEFAULT , AP_PARAM_FRAME_ROVER ) ,
2020-06-13 06:37:40 -03:00
// @Group: BR_
// @Path: AP_OABendyRuler.cpp
AP_SUBGROUPPTR ( _oabendyruler , " BR_ " , 6 , AP_OAPathPlanner , AP_OABendyRuler ) ,
2020-05-21 05:37:45 -03:00
2019-05-10 02:59:31 -03:00
AP_GROUPEND
} ;
/// Constructor
AP_OAPathPlanner : : AP_OAPathPlanner ( )
{
_singleton = this ;
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
// perform any required initialisation
void AP_OAPathPlanner : : init ( )
{
// run background task looking for best alternative destination
switch ( _type ) {
case OA_PATHPLAN_DISABLED :
// do nothing
2019-06-29 02:51:55 -03:00
return ;
2019-05-10 02:59:31 -03:00
case OA_PATHPLAN_BENDYRULER :
if ( _oabendyruler = = nullptr ) {
_oabendyruler = new AP_OABendyRuler ( ) ;
2020-06-13 06:37:40 -03:00
AP_Param : : load_object_from_eeprom ( _oabendyruler , AP_OABendyRuler : : var_info ) ;
2019-05-10 02:59:31 -03:00
}
break ;
case OA_PATHPLAN_DIJKSTRA :
if ( _oadijkstra = = nullptr ) {
_oadijkstra = new AP_OADijkstra ( ) ;
}
break ;
2020-08-24 04:04:35 -03:00
case OA_PATHPLAN_DJIKSTRA_BENDYRULER :
if ( _oadijkstra = = nullptr ) {
_oadijkstra = new AP_OADijkstra ( ) ;
}
if ( _oabendyruler = = nullptr ) {
_oabendyruler = new AP_OABendyRuler ( ) ;
AP_Param : : load_object_from_eeprom ( _oabendyruler , AP_OABendyRuler : : var_info ) ;
}
break ;
2019-05-10 02:59:31 -03:00
}
2019-06-29 02:51:55 -03:00
_oadatabase . init ( ) ;
start_thread ( ) ;
2019-05-10 02:59:31 -03:00
}
2020-07-01 03:11:09 -03:00
// return type of BendyRuler in use
2021-03-17 02:52:00 -03:00
AP_OABendyRuler : : OABendyType AP_OAPathPlanner : : get_bendy_type ( ) const
2020-07-01 03:11:09 -03:00
{
if ( _oabendyruler = = nullptr ) {
return AP_OABendyRuler : : OABendyType : : OA_BENDY_DISABLED ;
}
return _oabendyruler - > get_type ( ) ;
}
2019-05-10 02:59:31 -03:00
// pre-arm checks that algorithms have been initialised successfully
bool AP_OAPathPlanner : : pre_arm_check ( char * failure_msg , uint8_t failure_msg_len ) const
{
// check if initialisation has succeeded
switch ( _type ) {
case OA_PATHPLAN_DISABLED :
// do nothing
break ;
case OA_PATHPLAN_BENDYRULER :
if ( _oabendyruler = = nullptr ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " BendyRuler OA requires reboot " ) ;
return false ;
}
break ;
case OA_PATHPLAN_DIJKSTRA :
if ( _oadijkstra = = nullptr ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " Dijkstra OA requires reboot " ) ;
return false ;
}
break ;
2020-08-24 04:04:35 -03:00
case OA_PATHPLAN_DJIKSTRA_BENDYRULER :
if ( _oadijkstra = = nullptr | | _oabendyruler = = nullptr ) {
hal . util - > snprintf ( failure_msg , failure_msg_len , " OA requires reboot " ) ;
return false ;
}
break ;
2019-05-10 02:59:31 -03:00
}
return true ;
}
2019-06-29 02:51:55 -03:00
bool AP_OAPathPlanner : : start_thread ( )
{
WITH_SEMAPHORE ( _rsem ) ;
if ( _thread_created ) {
return true ;
}
if ( _type = = OA_PATHPLAN_DISABLED ) {
return false ;
}
// create the avoidance thread as low priority. It should soak
// up spare CPU cycles to fill in the avoidance_result structure based
// on requests in avoidance_request
if ( ! hal . scheduler - > thread_create ( FUNCTOR_BIND_MEMBER ( & AP_OAPathPlanner : : avoidance_thread , void ) ,
" avoidance " ,
8192 , AP_HAL : : Scheduler : : PRIORITY_IO , - 1 ) ) {
return false ;
}
_thread_created = true ;
return true ;
}
2019-05-10 02:59:31 -03:00
// provides an alternative target location if path planning around obstacles is required
// returns true and updates result_loc with an intermediate location
2019-06-26 04:15:41 -03:00
AP_OAPathPlanner : : OA_RetState AP_OAPathPlanner : : mission_avoidance ( const Location & current_loc ,
2019-05-10 02:59:31 -03:00
const Location & origin ,
const Location & destination ,
Location & result_origin ,
Location & result_destination )
{
2019-06-29 02:51:55 -03:00
// exit immediately if disabled or thread is not running from a failed init
if ( _type = = OA_PATHPLAN_DISABLED | | ! _thread_created ) {
2019-06-26 04:15:41 -03:00
return OA_NOT_REQUIRED ;
2019-05-10 02:59:31 -03:00
}
const uint32_t now = AP_HAL : : millis ( ) ;
2019-06-29 02:51:55 -03:00
WITH_SEMAPHORE ( _rsem ) ;
2019-05-10 02:59:31 -03:00
// place new request for the thread to work on
avoidance_request . current_loc = current_loc ;
avoidance_request . origin = origin ;
avoidance_request . destination = destination ;
avoidance_request . ground_speed_vec = AP : : ahrs ( ) . groundspeed_vector ( ) ;
avoidance_request . request_time_ms = now ;
2019-06-26 04:15:41 -03:00
// check result's destination matches our request
const bool destination_matches = ( destination . lat = = avoidance_result . destination . lat ) & & ( destination . lng = = avoidance_result . destination . lng ) ;
// check results have not timed out
const bool timed_out = now - avoidance_result . result_time_ms > OA_TIMEOUT_MS ;
2019-05-10 02:59:31 -03:00
// return results from background thread's latest checks
2019-06-26 04:15:41 -03:00
if ( destination_matches & & ! timed_out ) {
2019-05-10 02:59:31 -03:00
// we have a result from the thread
result_origin = avoidance_result . origin_new ;
result_destination = avoidance_result . destination_new ;
2019-06-26 04:15:41 -03:00
return avoidance_result . ret_state ;
2019-05-10 02:59:31 -03:00
}
2019-06-26 04:15:41 -03:00
// if timeout then path planner is taking too long to respond
if ( timed_out ) {
return OA_ERROR ;
}
// background thread is working on a new destination
return OA_PROCESSING ;
2019-05-10 02:59:31 -03:00
}
// avoidance thread that continually updates the avoidance_result structure based on avoidance_request
void AP_OAPathPlanner : : avoidance_thread ( )
2021-03-15 23:19:06 -03:00
{
2020-06-16 08:17:16 -03:00
// require ekf origin to have been set
bool origin_set = false ;
while ( ! origin_set ) {
hal . scheduler - > delay ( 500 ) ;
struct Location ekf_origin { } ;
{
WITH_SEMAPHORE ( AP : : ahrs ( ) . get_semaphore ( ) ) ;
origin_set = AP : : ahrs ( ) . get_origin ( ekf_origin ) ;
}
}
2019-05-10 02:59:31 -03:00
while ( true ) {
2019-06-29 02:51:55 -03:00
// if database queue needs attention, service it faster
if ( _oadatabase . process_queue ( ) ) {
hal . scheduler - > delay ( 1 ) ;
} else {
hal . scheduler - > delay ( 20 ) ;
}
2019-05-10 02:59:31 -03:00
2019-06-29 02:51:55 -03:00
const uint32_t now = AP_HAL : : millis ( ) ;
2019-12-09 07:07:31 -04:00
if ( now - avoidance_latest_ms < OA_UPDATE_MS ) {
2019-06-29 02:51:55 -03:00
continue ;
}
avoidance_latest_ms = now ;
_oadatabase . update ( ) ;
2019-05-10 02:59:31 -03:00
Location origin_new ;
Location destination_new ;
{
WITH_SEMAPHORE ( _rsem ) ;
if ( now - avoidance_request . request_time_ms > OA_TIMEOUT_MS ) {
// this is a very old request, don't process it
continue ;
}
// copy request to avoid conflict with main thread
avoidance_request2 = avoidance_request ;
// store passed in origin and destination so we can return it if object avoidance is not required
origin_new = avoidance_request . origin ;
destination_new = avoidance_request . destination ;
}
// run background task looking for best alternative destination
2019-06-26 04:15:41 -03:00
OA_RetState res = OA_NOT_REQUIRED ;
2019-05-10 02:59:31 -03:00
switch ( _type ) {
case OA_PATHPLAN_DISABLED :
continue ;
case OA_PATHPLAN_BENDYRULER :
if ( _oabendyruler = = nullptr ) {
continue ;
}
2020-06-13 06:37:40 -03:00
_oabendyruler - > set_config ( _margin_max ) ;
2020-08-24 04:04:35 -03:00
if ( _oabendyruler - > update ( avoidance_request2 . current_loc , avoidance_request2 . destination , avoidance_request2 . ground_speed_vec , origin_new , destination_new , false ) ) {
2019-06-26 04:15:41 -03:00
res = OA_SUCCESS ;
}
2019-05-10 02:59:31 -03:00
break ;
2019-06-29 02:51:55 -03:00
2020-08-24 04:04:35 -03:00
case OA_PATHPLAN_DIJKSTRA : {
2019-05-10 02:59:31 -03:00
if ( _oadijkstra = = nullptr ) {
continue ;
}
_oadijkstra - > set_fence_margin ( _margin_max ) ;
2019-06-26 04:15:41 -03:00
const AP_OADijkstra : : AP_OADijkstra_State dijkstra_state = _oadijkstra - > update ( avoidance_request2 . current_loc , avoidance_request2 . destination , origin_new , destination_new ) ;
switch ( dijkstra_state ) {
case AP_OADijkstra : : DIJKSTRA_STATE_NOT_REQUIRED :
res = OA_NOT_REQUIRED ;
break ;
case AP_OADijkstra : : DIJKSTRA_STATE_ERROR :
res = OA_ERROR ;
break ;
case AP_OADijkstra : : DIJKSTRA_STATE_SUCCESS :
res = OA_SUCCESS ;
break ;
}
2019-05-10 02:59:31 -03:00
break ;
}
2020-08-24 04:04:35 -03:00
case OA_PATHPLAN_DJIKSTRA_BENDYRULER : {
if ( ( _oabendyruler = = nullptr ) | | _oadijkstra = = nullptr ) {
continue ;
}
_oabendyruler - > set_config ( _margin_max ) ;
if ( _oabendyruler - > update ( avoidance_request2 . current_loc , avoidance_request2 . destination , avoidance_request2 . ground_speed_vec , origin_new , destination_new , proximity_only ) ) {
// detected a obstacle by vehicle's proximity sensor. Switch avoidance to BendyRuler till obstacle is out of the way
proximity_only = false ;
res = OA_SUCCESS ;
break ;
} else {
// cleared all obstacles, trigger Dijkstra's to calculate path based on current deviated position
if ( proximity_only = = false ) {
_oadijkstra - > recalculate_path ( ) ;
}
// only use proximity avoidance now for BendyRuler
proximity_only = true ;
}
_oadijkstra - > set_fence_margin ( _margin_max ) ;
const AP_OADijkstra : : AP_OADijkstra_State dijkstra_state = _oadijkstra - > update ( avoidance_request2 . current_loc , avoidance_request2 . destination , origin_new , destination_new ) ;
switch ( dijkstra_state ) {
case AP_OADijkstra : : DIJKSTRA_STATE_NOT_REQUIRED :
res = OA_NOT_REQUIRED ;
break ;
case AP_OADijkstra : : DIJKSTRA_STATE_ERROR :
res = OA_ERROR ;
break ;
case AP_OADijkstra : : DIJKSTRA_STATE_SUCCESS :
res = OA_SUCCESS ;
break ;
}
break ;
}
}
2019-05-10 02:59:31 -03:00
{
// give the main thread the avoidance result
WITH_SEMAPHORE ( _rsem ) ;
avoidance_result . destination = avoidance_request2 . destination ;
2019-07-24 02:38:39 -03:00
avoidance_result . origin_new = ( res = = OA_SUCCESS ) ? origin_new : avoidance_result . origin_new ;
avoidance_result . destination_new = ( res = = OA_SUCCESS ) ? destination_new : avoidance_result . destination ;
2019-05-10 02:59:31 -03:00
avoidance_result . result_time_ms = AP_HAL : : millis ( ) ;
2019-06-26 04:15:41 -03:00
avoidance_result . ret_state = res ;
2019-05-10 02:59:31 -03:00
}
}
}
// singleton instance
AP_OAPathPlanner * AP_OAPathPlanner : : _singleton ;
namespace AP {
AP_OAPathPlanner * ap_oapathplanner ( )
{
return AP_OAPathPlanner : : get_singleton ( ) ;
}
}