GCS_ServoRelay.cpp 1.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445
  1. #include "GCS.h"
  2. #include "AP_ServoRelayEvents/AP_ServoRelayEvents.h"
  3. MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &packet)
  4. {
  5. AP_ServoRelayEvents *handler = AP::servorelayevents();
  6. if (handler == nullptr) {
  7. return MAV_RESULT_UNSUPPORTED;
  8. }
  9. MAV_RESULT result = MAV_RESULT_FAILED;
  10. switch (packet.command) {
  11. case MAV_CMD_DO_SET_SERVO:
  12. if (handler->do_set_servo(packet.param1, packet.param2)) {
  13. result = MAV_RESULT_ACCEPTED;
  14. }
  15. break;
  16. case MAV_CMD_DO_REPEAT_SERVO:
  17. if (handler->do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4 * 1000)) {
  18. result = MAV_RESULT_ACCEPTED;
  19. }
  20. break;
  21. case MAV_CMD_DO_SET_RELAY:
  22. if (handler->do_set_relay(packet.param1, packet.param2)) {
  23. result = MAV_RESULT_ACCEPTED;
  24. }
  25. break;
  26. case MAV_CMD_DO_REPEAT_RELAY:
  27. if (handler->do_repeat_relay(packet.param1, packet.param2, packet.param3 * 1000)) {
  28. result = MAV_RESULT_ACCEPTED;
  29. }
  30. break;
  31. default:
  32. result = MAV_RESULT_UNSUPPORTED;
  33. break;
  34. }
  35. return result;
  36. }