diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index 9539ded757..91a2685c60 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -406,4 +406,25 @@ bool GCS_MAVLINK::check_payload_size(uint16_t max_payload_len) return true; } +#if AP_SCRIPTING_ENABLED +/* + lua access to command_int + + Note that this is called with the AP_Scheduler lock, ensuring the + main thread does not race with a lua command_int +*/ +MAV_RESULT GCS::lua_command_int_packet(const mavlink_command_int_t &packet) +{ + // for now we assume channel 0. In the future we may create a dedicated channel + auto *ch = chan(0); + if (ch == nullptr) { + return MAV_RESULT_UNSUPPORTED; + } + // we need a dummy message for some calls + mavlink_message_t msg {}; + + return ch->handle_command_int_packet(packet, msg); +} +#endif // AP_SCRIPTING_ENABLED + #endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 59b86fbb1c..9e5e7745a4 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -1271,6 +1271,11 @@ public: virtual uint8_t sysid_this_mav() const = 0; +#if AP_SCRIPTING_ENABLED + // lua access to command_int + MAV_RESULT lua_command_int_packet(const mavlink_command_int_t &packet); +#endif + protected: virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,