2017-07-13 23:44:21 -03:00
|
|
|
#include "GCS.h"
|
|
|
|
|
|
|
|
#include "AP_ServoRelayEvents/AP_ServoRelayEvents.h"
|
|
|
|
|
2023-06-06 05:05:06 -03:00
|
|
|
#if AP_SERVORELAYEVENTS_ENABLED
|
|
|
|
|
2018-07-03 23:16:16 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &packet)
|
2017-07-13 23:44:21 -03:00
|
|
|
{
|
2018-04-14 01:53:38 -03:00
|
|
|
AP_ServoRelayEvents *handler = AP::servorelayevents();
|
2017-07-13 23:44:21 -03:00
|
|
|
if (handler == nullptr) {
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
|
|
|
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
|
|
|
|
|
|
|
switch (packet.command) {
|
|
|
|
case MAV_CMD_DO_SET_SERVO:
|
|
|
|
if (handler->do_set_servo(packet.param1, packet.param2)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_DO_REPEAT_SERVO:
|
|
|
|
if (handler->do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4 * 1000)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2023-06-06 05:05:06 -03:00
|
|
|
#if AP_RELAY_ENABLED
|
2017-07-13 23:44:21 -03:00
|
|
|
case MAV_CMD_DO_SET_RELAY:
|
|
|
|
if (handler->do_set_relay(packet.param1, packet.param2)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_DO_REPEAT_RELAY:
|
|
|
|
if (handler->do_repeat_relay(packet.param1, packet.param2, packet.param3 * 1000)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
2023-06-06 05:05:06 -03:00
|
|
|
#endif
|
2017-07-13 23:44:21 -03:00
|
|
|
|
|
|
|
default:
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
return result;
|
|
|
|
}
|
2023-06-06 05:05:06 -03:00
|
|
|
|
|
|
|
#endif
|