|
|
|
@ -41,6 +41,7 @@
@@ -41,6 +41,7 @@
|
|
|
|
|
#include <AP_Baro/AP_Baro.h> |
|
|
|
|
#include <AP_EFI/AP_EFI.h> |
|
|
|
|
#include <AP_Proximity/AP_Proximity.h> |
|
|
|
|
#include <AP_Scripting/AP_Scripting.h> |
|
|
|
|
|
|
|
|
|
#include <stdio.h> |
|
|
|
|
|
|
|
|
@ -4053,6 +4054,16 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
@@ -4053,6 +4054,16 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|
|
|
|
return handle_command_do_set_roi_sysid(packet); |
|
|
|
|
case MAV_CMD_DO_SET_HOME: |
|
|
|
|
return handle_command_int_do_set_home(packet); |
|
|
|
|
#ifdef ENABLE_SCRIPTING |
|
|
|
|
case MAV_CMD_SCRIPTING: |
|
|
|
|
{ |
|
|
|
|
AP_Scripting *scripting = AP_Scripting::get_singleton(); |
|
|
|
|
if (scripting == nullptr) { |
|
|
|
|
return MAV_RESULT_UNSUPPORTED; |
|
|
|
|
} |
|
|
|
|
return scripting->handle_command_int_packet(packet); |
|
|
|
|
} |
|
|
|
|
#endif // ENABLE_SCRIPTING
|
|
|
|
|
default: |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|