8     if (handler == 
nullptr) {
     9         return MAV_RESULT_UNSUPPORTED;
    12     MAV_RESULT 
result = MAV_RESULT_FAILED;
    14     switch (packet.command) {
    15     case MAV_CMD_DO_SET_SERVO:
    16         if (handler->
do_set_servo(packet.param1, packet.param2)) {
    17             result = MAV_RESULT_ACCEPTED;
    21     case MAV_CMD_DO_REPEAT_SERVO:
    22         if (handler->
do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4 * 1000)) {
    23             result = MAV_RESULT_ACCEPTED;
    27     case MAV_CMD_DO_SET_RELAY:
    28         if (handler->
do_set_relay(packet.param1, packet.param2)) {
    29             result = MAV_RESULT_ACCEPTED;
    33     case MAV_CMD_DO_REPEAT_RELAY:
    34         if (handler->
do_repeat_relay(packet.param1, packet.param2, packet.param3 * 1000)) {
    35             result = MAV_RESULT_ACCEPTED;
    40         result = MAV_RESULT_UNSUPPORTED;
 bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms)
 
AP_ServoRelayEvents * servorelayevents()
 
Interface definition for the various Ground Control System. 
 
bool do_set_servo(uint8_t channel, uint16_t pwm)
 
bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms)
 
MAV_RESULT handle_servorelay_message(mavlink_command_long_t &packet)
 
bool do_set_relay(uint8_t relay_num, uint8_t state)
 
GCS_MAVLINK::protocol_handler_fn_t handler