AP_CANManager: reorganize precompiler for HAL_ENABLE_LIBUAVCAN_DRIVERS and HAL_MAX_PROTOCOL_DRIVERS

This commit is contained in:
Tom Pittenger 2021-04-30 18:29:55 -07:00 committed by Andrew Tridgell
parent f764bd6547
commit bdf0efbbe7
7 changed files with 9 additions and 7 deletions

View File

@ -15,7 +15,7 @@
#include <AP_HAL/AP_HAL.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_CANManager.h"
#include <AP_Vehicle/AP_Vehicle.h>

View File

@ -15,7 +15,7 @@
#include <AP_HAL/AP_HAL.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_CANManager.h"
// table of user settable CAN bus parameters

View File

@ -20,7 +20,7 @@
#include <AP_Common/AP_Common.h>
#include "AP_CANManager.h"
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_UAVCAN/AP_UAVCAN.h>

View File

@ -20,7 +20,7 @@
#include <AP_Common/AP_Common.h>
#include "AP_CANManager.h"
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_MAX_CAN_PROTOCOL_DRIVERS
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_CANTester.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <stdio.h>

View File

@ -18,7 +18,7 @@
#include "AP_CANDriver.h"
#include <AP_HAL/Semaphores.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_LIBUAVCAN_DRIVERS
class CANTester : public AP_CANDriver
{

View File

@ -19,7 +19,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_MAX_CAN_PROTOCOL_DRIVERS
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_CANTester_KDECAN.h"
#include "AP_CANManager.h"
#include <AP_Math/AP_Math.h>

View File

@ -245,7 +245,9 @@ bool SLCAN::CANIface::init_passthrough(uint8_t i)
_can_iface = hal.can[i];
_iface_num = _slcan_can_port - 1;
_prev_ser_port = -1;
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Setting SLCAN Passthrough for CAN%d\n", _slcan_can_port - 1);
#endif
return true;
}
@ -483,7 +485,7 @@ void SLCAN::CANIface::update_slcan_port()
}
_port->lock_port(_serial_lock_key, _serial_lock_key);
_prev_ser_port = _slcan_ser_port;
gcs().send_text(MAV_SEVERITY_INFO, "CANManager: Starting SLCAN Passthrough on Serial %d with CAN%d", _slcan_ser_port.get(), _iface_num);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CANManager: Starting SLCAN Passthrough on Serial %d with CAN%d", _slcan_ser_port.get(), _iface_num);
_last_had_activity = AP_HAL::native_millis();
}
if (_port == nullptr) {