HAL_ChibiOS: disable code for CAN for non UAVCAN supported

This commit is contained in:
Siddharth Purohit 2019-01-19 13:27:52 +08:00 committed by Andrew Tridgell
parent f6d165d8c1
commit 664c952460
8 changed files with 41 additions and 0 deletions

View File

@ -38,6 +38,9 @@
* Modified for Ardupilot by Siddharth Bharat Purohit
*/
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include "CANClock.h"
#include "CANThread.h"
#include "CANInternal.h"
@ -406,3 +409,4 @@ UAVCAN_STM32_IRQ_HANDLER(TIMX_IRQHandler)
}
#endif
#endif //HAL_WITH_UAVCAN

View File

@ -40,6 +40,9 @@
#pragma once
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include <uavcan/driver/system_clock.hpp>
namespace ChibiOS_CAN {
@ -159,3 +162,4 @@ public:
};
}
#endif //HAL_WITH_UAVCAN

View File

@ -40,6 +40,10 @@
#pragma once
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include "CANThread.h"
#include "CANIface.h"
#include "bxcan.hpp"
@ -440,3 +444,5 @@ public:
}
#include "CANSerialRouter.h"
#endif //HAL_WITH_UAVCAN

View File

@ -40,6 +40,10 @@
#pragma once
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include <hal.h>
#include <ch.h>
/**
@ -97,3 +101,5 @@ namespace clock {
uint64_t getUtcUSecFromCanInterrupt();
}
}
#endif //HAL_WITH_UAVCAN

View File

@ -38,6 +38,9 @@
* Modified for Ardupilot by Siddharth Bharat Purohit
*/
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include "CANThread.h"
#include "CANClock.h"
#include "CANIface.h"
@ -115,3 +118,5 @@ void Mutex::unlock()
}
}
#endif //HAL_WITH_UAVCAN

View File

@ -40,6 +40,10 @@
#pragma once
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
# include <ch.hpp>
#include <uavcan/uavcan.hpp>
@ -89,3 +93,5 @@ public:
};
}
#endif //HAL_WITH_UAVCAN

View File

@ -38,6 +38,9 @@
* Code by Siddharth Bharat Purohit
*/
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include <cassert>
#include <cstring>
#include "CANIface.h"
@ -1242,3 +1245,5 @@ UAVCAN_STM32_IRQ_HANDLER(CAN2_RX1_IRQHandler)
# endif
} // extern "C"
#endif //HAL_WITH_UAVCAN

View File

@ -40,6 +40,10 @@
#pragma once
#include "AP_HAL_ChibiOS.h"
#if HAL_WITH_UAVCAN
#include <uavcan_stm32/build_config.hpp>
#include <uavcan/uavcan.hpp>
@ -322,3 +326,4 @@ constexpr unsigned long FMR_FINIT = (1U << 0); /* Bit 0: Filter Init
#if UAVCAN_CPP_VERSION < UAVCAN_CPP11
# undef constexpr
#endif
#endif //HAL_WITH_UAVCAN