APM:Libraries
GCS_ServoRelay.cpp
Go to the documentation of this file.
1 #include "GCS.h"
2 
4 
5 MAV_RESULT GCS_MAVLINK::handle_servorelay_message(mavlink_command_long_t &packet)
6 {
8  if (handler == nullptr) {
9  return MAV_RESULT_UNSUPPORTED;
10  }
11 
12  MAV_RESULT result = MAV_RESULT_FAILED;
13 
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;
18  }
19  break;
20 
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;
24  }
25  break;
26 
27  case MAV_CMD_DO_SET_RELAY:
28  if (handler->do_set_relay(packet.param1, packet.param2)) {
29  result = MAV_RESULT_ACCEPTED;
30  }
31  break;
32 
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;
36  }
37  break;
38 
39  default:
40  result = MAV_RESULT_UNSUPPORTED;
41  break;
42  }
43 
44  return result;
45 }
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)
const char * result
Definition: Printf.cpp:16
bool do_set_relay(uint8_t relay_num, uint8_t state)