51 #define SBUS_CHANNELS 16 52 #define SBUS_MIN 880.0f 53 #define SBUS_MAX 2156.0f 54 #define SBUS_SCALE (2048.0f / (SBUS_MAX - SBUS_MIN)) 94 static uint32_t last_micros = 0;
105 for (
unsigned i = 0; i < nchan; ++i) {
113 if (value > 0x07ff) {
118 static uint16_t lastch9 = 0;
119 if ((i==8) && (pwmval != lastch9)) {
125 while (offset >= 8) {
130 buffer[index] |= (value << (offset)) & 0xff;
131 buffer[index + 1] |= (value >> (8 - offset)) & 0xff;
132 buffer[index + 2] |= (value >> (16 - offset)) & 0xff;
167 if (!serial_manager) {
static AP_SerialManager serial_manager
AP_HAL::UARTDriver * console
static uint8_t buffer[SRXL_FRAMELEN_MAX]
#define AP_GROUPINFO(name, idx, clazz, element, def)
AP_HAL::UARTDriver * sbus1_uart
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void write(uint8_t pin, uint8_t value)=0
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
static const struct AP_Param::GroupInfo var_info[]
static SRV_Channel * srv_channel(uint8_t i)
virtual void printf(const char *,...) FMT_PRINTF(2
virtual size_t write(uint8_t)=0
virtual void pinMode(uint8_t pin, uint8_t output)=0
static AP_SerialManager * get_instance(void)
uint16_t get_output_pwm(void) const
uint16_t sbus_frame_interval
#define NUM_SERVO_CHANNELS
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)