AP_RangeFinder: make AP_RANGEFINDER_ENABLED remove more code

This commit is contained in:
Peter Barker 2023-11-08 09:23:40 +11:00 committed by Andrew Tridgell
parent 37964011df
commit f9a94fd7dd
9 changed files with 51 additions and 8 deletions

View File

@ -14,6 +14,9 @@
*/
#include "AP_RangeFinder.h"
#if AP_RANGEFINDER_ENABLED
#include "AP_RangeFinder_analog.h"
#include "AP_RangeFinder_PulsedLightLRF.h"
#include "AP_RangeFinder_MaxsonarI2CXL.h"
@ -273,7 +276,6 @@ bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend, uint8_t instance
*/
void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
{
#if AP_RANGEFINDER_ENABLED
AP_RangeFinder_Backend_Serial *(*serial_create_fn)(RangeFinder::RangeFinder_State&, AP_RangeFinder_Params&) = nullptr;
const Type _type = (Type)params[instance].type.get();
@ -618,7 +620,6 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
// param count could have changed
AP_Param::invalidate_count();
}
#endif //AP_RANGEFINDER_ENABLED
}
AP_RangeFinder_Backend *RangeFinder::get_backend(uint8_t id) const {
@ -925,3 +926,4 @@ RangeFinder *rangefinder()
}
#endif // AP_RANGEFINDER_ENABLED

View File

@ -16,6 +16,8 @@
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_HAL/Semaphores.h>
@ -319,3 +321,5 @@ private:
namespace AP {
RangeFinder *rangefinder();
};
#endif // AP_RANGEFINDER_ENABLED

View File

@ -13,6 +13,10 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder.h"
@ -89,3 +93,4 @@ void AP_RangeFinder_Backend::get_state(RangeFinder::RangeFinder_State &state_arg
}
#endif
#endif // AP_RANGEFINDER_ENABLED

View File

@ -14,6 +14,10 @@
*/
#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_HAL/Semaphores.h>
@ -100,3 +104,5 @@ protected:
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0;
};
#endif // AP_RANGEFINDER_ENABLED

View File

@ -13,6 +13,10 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_Backend_Serial.h"
#include <AP_SerialManager/AP_SerialManager.h>
@ -61,3 +65,5 @@ void AP_RangeFinder_Backend_Serial::update(void)
set_status(RangeFinder::Status::NoData);
}
}
#endif // AP_RANGEFINDER_ENABLED

View File

@ -1,5 +1,9 @@
#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include "AP_RangeFinder_Backend.h"
class AP_RangeFinder_Backend_Serial : public AP_RangeFinder_Backend
@ -38,3 +42,5 @@ protected:
// maximum time between readings before we change state to NoData:
virtual uint16_t read_timeout_ms() const { return 200; }
};
#endif // AP_RANGEFINDER_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include "AP_RangeFinder_Params.h"
#include "AP_RangeFinder.h"
@ -139,3 +143,5 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
AP_RangeFinder_Params::AP_RangeFinder_Params(void) {
AP_Param::setup_object_defaults(this, var_info);
}
#endif // AP_RANGEFINDER_ENABLED

View File

@ -1,5 +1,9 @@
#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_ENABLED
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
@ -27,3 +31,5 @@ public:
AP_Int8 address;
AP_Int8 orientation;
};
#endif // AP_RANGEFINDER_ENABLED

View File

@ -1,6 +1,7 @@
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_MSP/AP_MSP_config.h>
#include <AP_Scripting/AP_Scripting_config.h>
#include <AP_CANManager/AP_CANManager_config.h>
#include <AP_MSP/AP_MSP_config.h>
@ -19,10 +20,7 @@
#endif
#ifndef AP_RANGEFINDER_BBB_PRU_ENABLED
#define AP_RANGEFINDER_BBB_PRU_ENABLED ( \
AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI \
)
#define AP_RANGEFINDER_BBB_PRU_ENABLED (AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI)
#endif
#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED
@ -94,7 +92,7 @@
#endif
#ifndef AP_RANGEFINDER_LUA_ENABLED
#define AP_RANGEFINDER_LUA_ENABLED AP_SCRIPTING_ENABLED
#define AP_RANGEFINDER_LUA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED
#endif
#ifndef AP_RANGEFINDER_MAVLINK_ENABLED
@ -110,7 +108,7 @@
#endif
#ifndef HAL_MSP_RANGEFINDER_ENABLED
#define HAL_MSP_RANGEFINDER_ENABLED HAL_MSP_ENABLED
#define HAL_MSP_RANGEFINDER_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_MSP_ENABLED
#endif
#ifndef AP_RANGEFINDER_NMEA_ENABLED
@ -141,6 +139,10 @@
#define AP_RANGEFINDER_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#ifndef HAL_MSP_RANGEFINDER_ENABLED
#define HAL_MSP_RANGEFINDER_ENABLED (AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_MSP_ENABLED)
#endif
#ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
#define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif