mirror of https://github.com/ArduPilot/ardupilot
Tools: use HAL_PROXIMITY_ENABLED in place of HAL_PERIPH_ENABLE_PRX
boolean truth rather than defines, and simplifies code
This commit is contained in:
parent
0ec35718d7
commit
5a33f870c0
|
@ -223,7 +223,7 @@ void AP_Periph_FW::init()
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_PRX
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
if (proximity.get_type(0) != AP_Proximity::Type::None && g.proximity_port >= 0) {
|
||||
auto *uart = hal.serial(g.proximity_port);
|
||||
if (uart != nullptr) {
|
||||
|
@ -564,4 +564,4 @@ AP_Periph_FW& AP::periph()
|
|||
return *AP_Periph_FW::get_singleton();
|
||||
}
|
||||
|
||||
AP_HAL_MAIN();
|
||||
AP_HAL_MAIN();
|
||||
|
|
|
@ -209,7 +209,7 @@ public:
|
|||
uint32_t last_sample_ms;
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_PRX
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
AP_Proximity proximity;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -475,7 +475,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
GOBJECT(efi, "EFI", AP_EFI),
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_PRX
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
// @Param: PRX_BAUDRATE
|
||||
// @DisplayName: Proximity Sensor serial baudrate
|
||||
// @Description: Proximity Sensor serial baudrate.
|
||||
|
@ -507,7 +507,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
// @Group: PRX
|
||||
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
||||
GOBJECT(proximity, "PRX", AP_Proximity),
|
||||
#endif
|
||||
#endif // HAL_PROXIMITY_ENABLED
|
||||
|
||||
#if HAL_NMEA_OUTPUT_ENABLED
|
||||
// @Group: NMEA_
|
||||
|
|
|
@ -109,7 +109,7 @@ public:
|
|||
AP_Int16 rangefinder_max_rate;
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_PRX
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
AP_Int32 proximity_baud;
|
||||
AP_Int8 proximity_port;
|
||||
AP_Int16 proximity_max_rate;
|
||||
|
@ -191,4 +191,4 @@ public:
|
|||
Parameters() {}
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -2392,7 +2392,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
|
|||
|
||||
void AP_Periph_FW::can_proximity_update()
|
||||
{
|
||||
#ifdef HAL_PERIPH_ENABLE_PRX
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
if (proximity.get_type(0) == AP_Proximity::Type::None) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -833,6 +833,7 @@ class sitl_periph_gps(sitl):
|
|||
AP_STATS_ENABLED = 0,
|
||||
HAL_SUPPORT_RCOUT_SERIAL = 0,
|
||||
AP_CAN_SLCAN_ENABLED = 0,
|
||||
HAL_PROXIMITY_ENABLED = 0,
|
||||
)
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue