mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: change UAVCAN_ENABLED to DRONECAN_ENABLED
This commit is contained in:
parent
f7a52557f6
commit
d2882c79de
|
@ -415,7 +415,7 @@ void AP_Airspeed::allocate()
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
case TYPE_UAVCAN:
|
case TYPE_UAVCAN:
|
||||||
#if AP_AIRSPEED_UAVCAN_ENABLED
|
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));
|
sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
@ -442,7 +442,7 @@ void AP_Airspeed::allocate()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AP_AIRSPEED_UAVCAN_ENABLED
|
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
// we need a 2nd pass for DroneCAN sensors so we can match order by DEVID
|
// we need a 2nd pass for DroneCAN sensors so we can match order by DEVID
|
||||||
// the 2nd pass accepts any devid
|
// the 2nd pass accepts any devid
|
||||||
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
||||||
|
@ -453,7 +453,7 @@ void AP_Airspeed::allocate()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // AP_AIRSPEED_UAVCAN_ENABLED
|
#endif // AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
#endif // HAL_AIRSPEED_PROBE_LIST
|
#endif // HAL_AIRSPEED_PROBE_LIST
|
||||||
|
|
||||||
// set DEVID to zero for any sensors not found. This allows backends to order
|
// set DEVID to zero for any sensors not found. This allows backends to order
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
#include "AP_Airspeed_DroneCAN.h"
|
#include "AP_Airspeed_DroneCAN.h"
|
||||||
|
|
||||||
#if AP_AIRSPEED_UAVCAN_ENABLED
|
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
|
|
||||||
#include <AP_CANManager/AP_CANManager.h>
|
#include <AP_CANManager/AP_CANManager.h>
|
||||||
#include <AP_DroneCAN/AP_DroneCAN.h>
|
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||||
|
@ -194,4 +194,4 @@ bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &tempera
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
|
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
|
||||||
#endif // AP_AIRSPEED_UAVCAN_ENABLED
|
#endif // AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
|
|
|
@ -2,11 +2,11 @@
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
#ifndef AP_AIRSPEED_UAVCAN_ENABLED
|
#ifndef AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS
|
#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_AIRSPEED_UAVCAN_ENABLED
|
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
|
|
||||||
#include "AP_Airspeed_Backend.h"
|
#include "AP_Airspeed_Backend.h"
|
||||||
|
|
||||||
|
@ -65,4 +65,4 @@ private:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif // AP_AIRSPEED_UAVCAN_ENABLED
|
#endif // AP_AIRSPEED_DRONECAN_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue