mirror of https://github.com/ArduPilot/ardupilot
AC_Avoidance: make _output_level AP_Enum
Also remove namespacing from OA_DbOutputLevel
This commit is contained in:
parent
75ef9a27cb
commit
1aa5a8f789
|
@ -68,7 +68,7 @@ const AP_Param::GroupInfo AP_OADatabase::var_info[] = {
|
|||
// @Description: OADatabase output level to configure which database objects are sent to the ground station. All data is always available internally for avoidance algorithms.
|
||||
// @Values: 0:Disabled,1:Send only HIGH importance items,2:Send HIGH and NORMAL importance items,3:Send all items
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OUTPUT", 4, AP_OADatabase, _output_level, (float)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH),
|
||||
AP_GROUPINFO("OUTPUT", 4, AP_OADatabase, _output_level, (float)OutputLevel::HIGH),
|
||||
|
||||
// @Param: BEAM_WIDTH
|
||||
// @DisplayName: OADatabase beam width
|
||||
|
@ -97,7 +97,7 @@ const AP_Param::GroupInfo AP_OADatabase::var_info[] = {
|
|||
|
||||
// @Param{Copter}: ALT_MIN
|
||||
// @DisplayName: OADatabase minimum altitude above home before storing obstacles
|
||||
// @Description: OADatabase will reject obstacle's if vehicle's altitude above home is below this parameter, in a 3 meter radius around home. Set 0 to disable this feature.
|
||||
// @Description: OADatabase will reject obstacles if vehicle's altitude above home is below this parameter, in a 3 meter radius around home. Set 0 to disable this feature.
|
||||
// @Units: m
|
||||
// @Range: 0 4
|
||||
// @User: Advanced
|
||||
|
@ -210,19 +210,19 @@ uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importanc
|
|||
{
|
||||
switch (importance) {
|
||||
case OA_DbItemImportance::Low:
|
||||
if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_ALL) {
|
||||
if (_output_level >= OutputLevel::ALL) {
|
||||
return 0xFF;
|
||||
}
|
||||
break;
|
||||
|
||||
case OA_DbItemImportance::Normal:
|
||||
if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH_AND_NORMAL) {
|
||||
if (_output_level >= OutputLevel::HIGH_AND_NORMAL) {
|
||||
return 0xFF;
|
||||
}
|
||||
break;
|
||||
|
||||
case OA_DbItemImportance::High:
|
||||
if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH) {
|
||||
if (_output_level >= OutputLevel::HIGH) {
|
||||
return 0xFF;
|
||||
}
|
||||
break;
|
||||
|
@ -372,7 +372,7 @@ void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_
|
|||
static_assert(MAVLINK_COMM_NUM_BUFFERS <= sizeof(OA_DbItem::send_to_gcs) * 8,
|
||||
"AP_OADatabase's OA_DBItem.send_to_gcs bitmask must be large enough to hold MAVLINK_COMM_NUM_BUFFERS");
|
||||
|
||||
if ((_output_level.get() <= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_DISABLED) || !healthy()) {
|
||||
if ((_output_level <= OutputLevel::NONE) || !healthy()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -74,18 +74,18 @@ private:
|
|||
bool is_close_to_item_in_database(const uint16_t index, const OA_DbItem &item) const;
|
||||
|
||||
// enum for use with _OUTPUT parameter
|
||||
enum class OA_DbOutputLevel {
|
||||
OUTPUT_LEVEL_DISABLED = 0,
|
||||
OUTPUT_LEVEL_SEND_HIGH = 1,
|
||||
OUTPUT_LEVEL_SEND_HIGH_AND_NORMAL = 2,
|
||||
OUTPUT_LEVEL_SEND_ALL = 3
|
||||
enum class OutputLevel {
|
||||
NONE = 0,
|
||||
HIGH = 1,
|
||||
HIGH_AND_NORMAL = 2,
|
||||
ALL = 3
|
||||
};
|
||||
|
||||
// parameters
|
||||
AP_Int16 _queue_size_param; // queue size
|
||||
AP_Int16 _database_size_param; // db size
|
||||
AP_Int8 _database_expiry_seconds; // objects expire after this timeout
|
||||
AP_Int8 _output_level; // controls which items should be sent to GCS
|
||||
AP_Enum<OutputLevel> _output_level; // controls which items should be sent to GCS
|
||||
AP_Float _beam_width; // beam width used when converting lidar readings to object radius
|
||||
AP_Float _radius_min; // objects minimum radius (in meters)
|
||||
AP_Float _dist_max; // objects maximum distance (in meters)
|
||||
|
|
Loading…
Reference in New Issue