|
|
@ -1330,30 +1330,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_SERVO: |
|
|
|
|
|
|
|
if (plane.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) { |
|
|
|
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_REPEAT_SERVO: |
|
|
|
|
|
|
|
if (plane.ServoRelayEvents.do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4*1000)) { |
|
|
|
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_RELAY: |
|
|
|
|
|
|
|
if (plane.ServoRelayEvents.do_set_relay(packet.param1, packet.param2)) { |
|
|
|
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_REPEAT_RELAY: |
|
|
|
|
|
|
|
if (plane.ServoRelayEvents.do_repeat_relay(packet.param1, packet.param2, packet.param3*1000)) { |
|
|
|
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: |
|
|
|
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: |
|
|
|
result = handle_preflight_reboot(packet, plane.quadplane.enable != 0); |
|
|
|
result = handle_preflight_reboot(packet, plane.quadplane.enable != 0); |
|
|
|
break; |
|
|
|
break; |
|
|
@ -2061,6 +2037,11 @@ void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_ |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
AP_ServoRelayEvents *GCS_MAVLINK_Plane::get_servorelayevents() const |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
return &plane.ServoRelayEvents; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
AP_Rally *GCS_MAVLINK_Plane::get_rally() const |
|
|
|
AP_Rally *GCS_MAVLINK_Plane::get_rally() const |
|
|
|
{ |
|
|
|
{ |
|
|
|
return &plane.rally; |
|
|
|
return &plane.rally; |
|
|
|