|
|
|
@ -642,6 +642,10 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
@@ -642,6 +642,10 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
|
|
|
|
|
{ |
|
|
|
|
#if HAL_ADSB_ENABLED |
|
|
|
|
plane.avoidance_adsb.handle_msg(msg); |
|
|
|
|
#endif |
|
|
|
|
#if SHIP_LANDING_ENABLED |
|
|
|
|
// pass message to follow library
|
|
|
|
|
plane.g2.follow.handle_msg(msg); |
|
|
|
|
#endif |
|
|
|
|
GCS_MAVLINK::packetReceived(status, msg); |
|
|
|
|
} |
|
|
|
@ -874,6 +878,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
@@ -874,6 +878,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|
|
|
|
case MAV_CMD_GUIDED_CHANGE_HEADING: |
|
|
|
|
return handle_command_int_guided_slew_commands(packet); |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_FOLLOW: |
|
|
|
|
#if SHIP_LANDING_ENABLED |
|
|
|
|
// param1: sysid of target to follow
|
|
|
|
|
if ((packet.param1 > 0) && (packet.param1 <= 255)) { |
|
|
|
|
plane.g2.follow.set_target_sysid((uint8_t)packet.param1); |
|
|
|
|
return MAV_RESULT_ACCEPTED; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
return MAV_RESULT_FAILED; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
return GCS_MAVLINK::handle_command_int_packet(packet); |
|
|
|
|
} |
|
|
|
@ -1075,6 +1089,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
@@ -1075,6 +1089,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|
|
|
|
} |
|
|
|
|
return MAV_RESULT_ACCEPTED; |
|
|
|
|
|
|
|
|
|
#if SHIP_LANDING_ENABLED |
|
|
|
|
case MAV_CMD_DO_FOLLOW: |
|
|
|
|
// param1: sysid of target to follow
|
|
|
|
|
if ((packet.param1 > 0) && (packet.param1 <= 255)) { |
|
|
|
|
plane.g2.follow.set_target_sysid((uint8_t)packet.param1); |
|
|
|
|
return MAV_RESULT_ACCEPTED; |
|
|
|
|
} |
|
|
|
|
return MAV_RESULT_FAILED; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
return GCS_MAVLINK::handle_command_long_packet(packet); |
|
|
|
|
} |
|
|
|
|