|
|
|
@ -54,18 +54,31 @@ class TrafficReportCb;
@@ -54,18 +54,31 @@ class TrafficReportCb;
|
|
|
|
|
class ActuatorStatusCb; |
|
|
|
|
class ESCStatusCb; |
|
|
|
|
|
|
|
|
|
#if defined(__GNUC__) && (__GNUC__ > 8) |
|
|
|
|
#define DISABLE_W_CAST_FUNCTION_TYPE_PUSH \ |
|
|
|
|
_Pragma("GCC diagnostic push") \
|
|
|
|
|
_Pragma("GCC diagnostic ignored \"-Wcast-function-type\"") |
|
|
|
|
#define DISABLE_W_CAST_FUNCTION_TYPE_POP \ |
|
|
|
|
_Pragma("GCC diagnostic pop") |
|
|
|
|
#else |
|
|
|
|
#define DISABLE_W_CAST_FUNCTION_TYPE_PUSH |
|
|
|
|
#define DISABLE_W_CAST_FUNCTION_TYPE_POP |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
Frontend Backend-Registry Binder: Whenever a message of said DataType_ from new node is received, |
|
|
|
|
the Callback will invoke registery to register the node as separate backend. |
|
|
|
|
*/ |
|
|
|
|
#define UC_REGISTRY_BINDER(ClassName_, DataType_) \ |
|
|
|
|
class ClassName_ : public AP_UAVCAN::RegistryBinder<DataType_> { \
|
|
|
|
|
class ClassName_ : public AP_UAVCAN::RegistryBinder<DataType_> { \
|
|
|
|
|
typedef void (*CN_Registry)(AP_UAVCAN*, uint8_t, const ClassName_&); \
|
|
|
|
|
public: \
|
|
|
|
|
ClassName_() : RegistryBinder() {} \
|
|
|
|
|
ClassName_(AP_UAVCAN* uc, CN_Registry ffunc) : \
|
|
|
|
|
RegistryBinder(uc, (Registry)ffunc) {} \
|
|
|
|
|
} |
|
|
|
|
public: \
|
|
|
|
|
ClassName_() : RegistryBinder() {} \
|
|
|
|
|
DISABLE_W_CAST_FUNCTION_TYPE_PUSH \
|
|
|
|
|
ClassName_(AP_UAVCAN* uc, CN_Registry ffunc) : \
|
|
|
|
|
RegistryBinder(uc, (Registry)ffunc) {} \
|
|
|
|
|
DISABLE_W_CAST_FUNCTION_TYPE_POP \
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
class AP_UAVCAN : public AP_CANDriver { |
|
|
|
|
public: |
|
|
|
|