Navigator: make ADSB handling optional

This commit is contained in:
Matthias Grob 2024-12-19 07:13:20 +01:00
parent 367a8a7fc4
commit 839010eeab
10 changed files with 32 additions and 7 deletions

View File

@ -32,6 +32,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set

View File

@ -36,6 +36,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=y

View File

@ -27,6 +27,7 @@ CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=y

View File

@ -40,6 +40,7 @@ CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set

View File

@ -31,6 +31,7 @@ CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set

View File

@ -40,6 +40,7 @@ CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set

View File

@ -32,6 +32,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NAVIGATOR_ADSB=n
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=y

View File

@ -19,3 +19,11 @@ menuconfig MODE_NAVIGATOR_VTOL_TAKEOFF
Add VTOL takeoff mode to enable support for MAV_CMD_NAV_VTOL_TAKEOFF.
The VTOL takes off in MC mode and transition to FW. The mode ends with
an infinite loiter
menuconfig NAVIGATOR_ADSB
bool "Include traffic reporting and avoidance"
default y
depends on MODULES_NAVIGATOR
---help---
Add support for acting on ADSB transponder_report or ADSB_VEHICLE MAVLink messages.
Actions are warnings, Loiter, Land and RTL without climb.

View File

@ -57,8 +57,11 @@
#include "GeofenceBreachAvoidance/geofence_breach_avoidance.h"
#if CONFIG_NAVIGATOR_ADSB
#include <lib/adsb/AdsbConflict.h>
#endif // CONFIG_NAVIGATOR_ADSB
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/events.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <uORB/Publication.hpp>
@ -136,14 +139,14 @@ public:
*/
void publish_vehicle_cmd(vehicle_command_s *vcmd);
#if CONFIG_NAVIGATOR_ADSB
/**
* Check nearby traffic for potential collisions
*/
void check_traffic();
void take_traffic_conflict_action();
void run_fake_traffic();
#endif // CONFIG_NAVIGATOR_ADSB
/**
* Setters
@ -365,7 +368,10 @@ private:
Land _land; /**< class for handling land commands */
PrecLand _precland; /**< class for handling precision land commands */
RTL _rtl; /**< class that handles RTL */
#if CONFIG_NAVIGATOR_ADSB
AdsbConflict _adsb_conflict; /**< class that handles ADSB conflict avoidance */
traffic_buffer_s _traffic_buffer{};
#endif // CONFIG_NAVIGATOR_ADSB
NavigatorMode *_navigation_mode{nullptr}; /**< abstract pointer to current navigation mode class */
NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE] {}; /**< array of navigation modes */
@ -381,8 +387,6 @@ private:
float _cruising_speed_current_mode{-1.0f};
float _mission_throttle{NAN};
traffic_buffer_s _traffic_buffer{};
bool _is_capturing_images{false}; // keep track if we need to stop capturing images

View File

@ -52,7 +52,6 @@
#include <dataman_client/DatamanClient.hpp>
#include <drivers/drv_hrt.h>
#include <lib/geo/geo.h>
#include <lib/adsb/AdsbConflict.h>
#include <lib/mathlib/mathlib.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
@ -143,9 +142,11 @@ void Navigator::params_update()
}
_mission.set_command_timeout(_param_mis_command_tout.get());
#if CONFIG_NAVIGATOR_ADSB
_adsb_conflict.set_conflict_detection_params(_param_nav_traff_a_hor_ct.get(),
_param_nav_traff_a_ver.get(),
_param_nav_traff_collision_time.get(), _param_nav_traff_avoid.get());
#endif // CONFIG_NAVIGATOR_ADSB
}
void Navigator::run()
@ -752,8 +753,10 @@ void Navigator::run()
}
}
#if CONFIG_NAVIGATOR_ADSB
/* Check for traffic */
check_traffic();
#endif // CONFIG_NAVIGATOR_ADSB
/* Check geofence violation */
geofence_breach_check();
@ -1222,6 +1225,7 @@ void Navigator::load_fence_from_file(const char *filename)
_geofence.loadFromFile(filename);
}
#if CONFIG_NAVIGATOR_ADSB
void Navigator::take_traffic_conflict_action()
{
@ -1251,12 +1255,10 @@ void Navigator::take_traffic_conflict_action()
}
}
}
void Navigator::run_fake_traffic()
{
_adsb_conflict.run_fake_traffic(get_global_position()->lat, get_global_position()->lon,
get_global_position()->alt);
}
@ -1283,6 +1285,7 @@ void Navigator::check_traffic()
_adsb_conflict.remove_expired_conflicts();
}
#endif // CONFIG_NAVIGATOR_ADSB
bool Navigator::abort_landing()
{
@ -1325,11 +1328,14 @@ int Navigator::custom_command(int argc, char *argv[])
get_instance()->load_fence_from_file(GEOFENCE_FILENAME);
return 0;
#if CONFIG_NAVIGATOR_ADSB
} else if (!strcmp(argv[0], "fake_traffic")) {
get_instance()->run_fake_traffic();
return 0;
#endif // CONFIG_NAVIGATOR_ADSB
}
return print_usage("unknown command");