30 #include "generated/airframe.h"
32 #if (defined DATALINK) || PERIODIC_TELEMETRY
36 #if USE_HARD_FAULT_RECOVERY
40 #if defined SITL && !USE_NPS
41 struct ivy_transport ivy_tp;
44 #if DATALINK == PPRZ || DATALINK == SUPERBITRF || DATALINK == W5100 || DATALINK == BLUEGIGA
45 struct pprz_transport pprz_tp;
48 struct xbee_transport xbee_tp;
51 struct pprzlog_transport pprzlog_tp;
54 #if PERIODIC_TELEMETRY
72 #if defined DATALINK || defined SITL
81 &up_rate, &dev->nb_ovrn);
98 pprz_transport_init(&pprz_tp);
102 #define XBEE_TYPE XBEE_24
107 #if USE_HARD_FAULT_RECOVERY
108 if (recovering_from_hard_fault)
110 xbee_transport_init(&xbee_tp, &((
DefaultDevice).device), AC_ID, XBEE_TYPE, XBEE_BAUD, NULL, XBEE_INIT);
115 #if DATALINK == W5100
118 #if DATALINK == BLUEGIGA
129 ivy_transport_init(&ivy_tp);
132 #if PERIODIC_TELEMETRY
Periodic telemetry system header (includes downlink utility and generated code).
uint32_t get_sys_time_msec(void)
static uint32_t last_up_nb_msgs
Handling of messages coming from ground and other A/Cs.
struct bluegiga_periph bluegiga_p
void bluegiga_init(struct bluegiga_periph *p)
uint16_t datalink_nb_msgs
void sys_time_usleep(uint32_t us)
sys_time_usleep(uint32_t us)
static uint32_t last_down_nb_bytes
Architecture independent timing functions.
#define DefaultPeriodic
Set default periodic telemetry.
static const struct usb_device_descriptor dev
static void send_downlink(struct transport_tx *trans, struct link_device *dev)
#define PPRZ
Datalink kinds.
Arch independent mcu ( Micro Controller Unit ) utilities.
Common code for AP and FBW telemetry.
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.