Geofence: remove GF_ALTMODE

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2023-11-16 13:47:12 +01:00 committed by Daniel Agar
parent f3eacb4844
commit fd709e05b0
3 changed files with 6 additions and 49 deletions

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013,2017 PX4 Development Team. All rights reserved.
* Copyright (c) 2013-2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -55,8 +55,7 @@
Geofence::Geofence(Navigator *navigator) :
ModuleParams(navigator),
_navigator(navigator),
_sub_airdata(ORB_ID(vehicle_air_data))
_navigator(navigator)
{
if (_navigator != nullptr) {
updateFence();
@ -250,11 +249,6 @@ bool Geofence::checkAll(const struct vehicle_global_position_s &global_position)
return checkAll(global_position.lat, global_position.lon, global_position.alt);
}
bool Geofence::checkAll(const struct vehicle_global_position_s &global_position, const float alt)
{
return checkAll(global_position.lat, global_position.lon, alt);
}
bool Geofence::checkAll(double lat, double lon, float altitude)
{
bool inside_fence = isCloserThanMaxDistToHome(lat, lon, altitude);
@ -283,25 +277,11 @@ bool Geofence::checkAll(double lat, double lon, float altitude)
bool Geofence::check(const vehicle_global_position_s &global_position, const sensor_gps_s &gps_position)
{
if (_param_gf_altmode.get() == Geofence::GF_ALT_MODE_WGS84) {
if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
return checkAll(global_position);
} else {
return checkAll(gps_position.latitude_deg, gps_position.longitude_deg, gps_position.altitude_msl_m);
}
if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
return checkAll(global_position);
} else {
// get baro altitude
_sub_airdata.update();
const float baro_altitude_amsl = _sub_airdata.get().baro_alt_meter;
if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
return checkAll(global_position, baro_altitude_amsl);
} else {
return checkAll(gps_position.latitude_deg, gps_position.longitude_deg, baro_altitude_amsl);
}
return checkAll(gps_position.latitude_deg, gps_position.longitude_deg, gps_position.altitude_msl_m);
}
}

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Copyright (c) 2013-2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -52,7 +52,6 @@
#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/sensor_gps.h>
#include <uORB/topics/vehicle_air_data.h>
#define GEOFENCE_FILENAME PX4_STORAGEDIR"/etc/geofence.txt"
@ -66,12 +65,6 @@ public:
Geofence &operator=(const Geofence &) = delete;
virtual ~Geofence();
/* Altitude mode, corresponding to the param GF_ALTMODE */
enum {
GF_ALT_MODE_WGS84 = 0,
GF_ALT_MODE_AMSL = 1
};
/* Source, corresponding to the param GF_SOURCE */
enum {
GF_SOURCE_GLOBALPOS = 0,
@ -195,7 +188,6 @@ private:
MapProjection _projection_reference{}; ///< class to convert (lon, lat) to local [m]
uORB::SubscriptionData<vehicle_air_data_s> _sub_airdata;
int _outside_counter{0};
uint16_t _update_counter{0}; ///< dataman update counter: if it does not match, polygon data was updated
@ -222,7 +214,6 @@ private:
bool checkAll(const vehicle_global_position_s &global_position);
bool checkAll(const vehicle_global_position_s &global_position, float baro_altitude_amsl);
/**
* Check if a single point is within a polygon
@ -239,7 +230,6 @@ private:
DEFINE_PARAMETERS(
(ParamInt<px4::params::GF_ACTION>) _param_gf_action,
(ParamInt<px4::params::GF_ALTMODE>) _param_gf_altmode,
(ParamInt<px4::params::GF_SOURCE>) _param_gf_source,
(ParamInt<px4::params::GF_COUNT>) _param_gf_count,
(ParamFloat<px4::params::GF_MAX_HOR_DIST>) _param_gf_max_hor_dist,

View File

@ -61,19 +61,6 @@
*/
PARAM_DEFINE_INT32(GF_ACTION, 2);
/**
* Geofence altitude mode
*
* Select which altitude (AMSL) source should be used for geofence calculations.
*
* @min 0
* @max 1
* @value 0 Autopilot estimator global position altitude (GPS)
* @value 1 Raw barometer altitude (assuming standard atmospheric pressure)
* @group Geofence
*/
PARAM_DEFINE_INT32(GF_ALTMODE, 0);
/**
* Geofence source
*