mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Add missing defines for Bebop sensor drivers
This commit is contained in:
parent
e73d8d73e1
commit
d94bdb0829
@ -5,6 +5,7 @@ set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linu
|
||||
add_definitions(
|
||||
-D__PX4_POSIX_BEBOP
|
||||
-D__LINUX
|
||||
-D__BEBOP
|
||||
)
|
||||
|
||||
set(CMAKE_PROGRAM_PATH
|
||||
@ -22,6 +23,7 @@ set(config_module_list
|
||||
drivers/device
|
||||
modules/sensors
|
||||
platforms/posix/drivers/df_ms5607_wrapper
|
||||
platforms/posix/drivers/df_mpu6050_wrapper
|
||||
|
||||
#
|
||||
# System commands
|
||||
@ -99,4 +101,5 @@ set(config_module_list
|
||||
|
||||
set(config_df_driver_list
|
||||
ms5607
|
||||
mpu6050
|
||||
)
|
||||
|
||||
@ -1017,7 +1017,7 @@ Sensors::parameters_update()
|
||||
DevHandle h_baro;
|
||||
DevMgr::getHandle(BARO0_DEVICE_PATH, h_baro);
|
||||
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
|
||||
// TODO: this needs fixing for QURT and Raspberry Pi
|
||||
if (!h_baro.isValid()) {
|
||||
@ -1671,7 +1671,7 @@ Sensors::parameter_update_poll(bool forced)
|
||||
bool
|
||||
Sensors::apply_gyro_calibration(DevHandle &h, const struct gyro_calibration_s *gcal, const int device_id)
|
||||
{
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
|
||||
/* On most systems, we can just use the IOCTL call to set the calibration params. */
|
||||
return !h.ioctl(GYROIOCSSCALE, (long unsigned int)gcal);
|
||||
@ -1685,7 +1685,7 @@ Sensors::apply_gyro_calibration(DevHandle &h, const struct gyro_calibration_s *g
|
||||
bool
|
||||
Sensors::apply_accel_calibration(DevHandle &h, const struct accel_calibration_s *acal, const int device_id)
|
||||
{
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
|
||||
/* On most systems, we can just use the IOCTL call to set the calibration params. */
|
||||
return !h.ioctl(ACCELIOCSSCALE, (long unsigned int)acal);
|
||||
@ -1699,7 +1699,7 @@ Sensors::apply_accel_calibration(DevHandle &h, const struct accel_calibration_s
|
||||
bool
|
||||
Sensors::apply_mag_calibration(DevHandle &h, const struct mag_calibration_s *mcal, const int device_id)
|
||||
{
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
|
||||
/* On most systems, we can just use the IOCTL call to set the calibration params. */
|
||||
return !h.ioctl(MAGIOCSSCALE, (long unsigned int)mcal);
|
||||
@ -2250,7 +2250,7 @@ Sensors::task_main()
|
||||
/* This calls a sensors_init which can have different implementations on NuttX, POSIX, QURT. */
|
||||
ret = sensors_init();
|
||||
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI)
|
||||
#if !defined(__PX4_QURT) && !defined(__PX4_POSIX_RPI) && !defined(__PX4_POSIX_BEBOP)
|
||||
// TODO: move adc_init into the sensors_init call.
|
||||
ret = ret || adc_init();
|
||||
#endif
|
||||
|
||||
@ -52,7 +52,7 @@
|
||||
|
||||
using namespace DriverFramework;
|
||||
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI)
|
||||
#if defined(__PX4_QURT) || defined(__PX4_POSIX_RPI) || defined(__PX4_POSIX_BEBOP)
|
||||
|
||||
// Sensor initialization is performed automatically when the QuRT sensor drivers
|
||||
// are loaded.
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user