148 if ((chan_mask & (1U<<i)) == 0) {
152 mavlink_channel_t
chan = (mavlink_channel_t)i;
154 mavlink_msg_button_change_send(chan,
#define AP_PARAM_FLAG_ENABLE
Interface definition for the various Ground Control System.
#define AP_GROUPINFO(name, idx, clazz, element, def)
static uint8_t active_channel_mask(void)
virtual void write(uint8_t pin, uint8_t value)=0
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
#define HAVE_PAYLOAD_SPACE(chan, id)
virtual void pinMode(uint8_t pin, uint8_t output)=0
virtual void register_timer_process(AP_HAL::MemberProc)=0
virtual uint8_t read(uint8_t pin)=0
AP_HAL::AnalogSource * chan
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
AP_HAL::Scheduler * scheduler
#define MAVLINK_COMM_NUM_BUFFERS
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)