mirror of https://github.com/ArduPilot/ardupilot
AP_PiccoloCAN: Add precompiler checks
- Only compile if HAL_PICCOLO_CAN_ENABLE flag is set
This commit is contained in:
parent
e6f1437ccf
commit
5e68e473c9
|
@ -21,6 +21,12 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
|
||||
#ifndef HAL_PICCOLO_CAN_ENABLE
|
||||
#define HAL_PICCOLO_CAN_ENABLE (HAL_NUM_CAN_IFACES && !HAL_MINIMIZE_FEATURES)
|
||||
#endif
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
// Piccolo message groups form part of the CAN ID of each frame
|
||||
enum class PiccoloCAN_MessageGroup : uint8_t {
|
||||
SIMULATOR = 0x00, // Simulator messages
|
||||
|
@ -66,3 +72,5 @@ public:
|
|||
//! Timestamp of most recently received CAN message
|
||||
uint64_t last_msg_timestamp = 0;
|
||||
};
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#include "AP_PiccoloCAN_ECU.h"
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
// Protocol files for the ECU
|
||||
#include <AP_PiccoloCAN/piccolo_protocol/ECUProtocol.h>
|
||||
#include <AP_PiccoloCAN/piccolo_protocol/ECUPackets.h>
|
||||
|
@ -88,3 +90,5 @@ uint32_t getECUPacketID(const void* pkt)
|
|||
// Extract the message ID field from the 29-bit ID
|
||||
return (uint32_t) ((frame->id >> 16) & 0xFF);
|
||||
}
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
|
@ -25,6 +25,8 @@
|
|||
|
||||
#define PICCOLO_CAN_ECU_ID_DEFAULT 0
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
/*
|
||||
* Class representing an individual PiccoloCAN ECU
|
||||
*/
|
||||
|
@ -33,3 +35,5 @@ class AP_PiccoloCAN_ECU : public AP_PiccoloCAN_Device
|
|||
public:
|
||||
// TODO
|
||||
};
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#include "AP_PiccoloCAN_ESC.h"
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
/*
|
||||
* Decode a recevied CAN frame.
|
||||
|
@ -146,3 +147,5 @@ uint32_t getESCVelocityPacketID(const void* pkt)
|
|||
// Extract the message ID field from the 29-bit ID
|
||||
return (uint32_t) ((frame->id >> 16) & 0xFF);
|
||||
}
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
||||
|
|
|
@ -25,6 +25,8 @@
|
|||
#include "AP_PiccoloCAN_Device.h"
|
||||
#include "piccolo_protocol/ESCPackets.h"
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
#define PICCOLO_CAN_MAX_NUM_ESC 16
|
||||
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
|
||||
|
||||
|
@ -70,3 +72,5 @@ public:
|
|||
ESC_EEPROMSettings_t eeprom;
|
||||
} settings;
|
||||
};
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#include "AP_PiccoloCAN_Servo.h"
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
/*
|
||||
* Decode a recevied CAN frame.
|
||||
|
@ -113,3 +114,5 @@ uint32_t getServoPacketID(const void* pkt)
|
|||
// Extract the message ID field from the 29-bit ID
|
||||
return (uint32_t) ((frame->id >> 16) & 0xFF);
|
||||
}
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
|
@ -22,6 +22,8 @@
|
|||
#include "AP_PiccoloCAN_Device.h"
|
||||
#include "piccolo_protocol/ServoPackets.h"
|
||||
|
||||
#if HAL_PICCOLO_CAN_ENABLE
|
||||
|
||||
#define PICCOLO_CAN_MAX_NUM_SERVO 16
|
||||
#define PICCOLO_CAN_MAX_GROUP_SERVO (PICCOLO_CAN_MAX_NUM_SERVO / 4)
|
||||
|
||||
|
@ -63,3 +65,5 @@ public:
|
|||
Servo_SettingsInfo_t settings;
|
||||
} settings;
|
||||
};
|
||||
|
||||
#endif // HAL_PICCOLO_CAN_ENABLE
|
||||
|
|
Loading…
Reference in New Issue