AP_Scripting: add some missing dependencies
This commit is contained in:
parent
82628c2559
commit
7bbd4a7c7d
@ -154,17 +154,18 @@ void AP_Scripting::init(void) {
|
||||
const char *dir_name = SCRIPTING_DIRECTORY;
|
||||
if (AP::FS().mkdir(dir_name)) {
|
||||
if (errno != EEXIST) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Scripting: failed to create (%s)", dir_name);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: failed to create (%s)", dir_name);
|
||||
}
|
||||
}
|
||||
|
||||
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Scripting::thread, void),
|
||||
"Scripting", SCRIPTING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_SCRIPTING, 0)) {
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start");
|
||||
_thread_failed = true;
|
||||
}
|
||||
}
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t &packet) {
|
||||
switch ((SCRIPTING_CMD)packet.param1) {
|
||||
case SCRIPTING_CMD_REPL_START:
|
||||
@ -186,6 +187,7 @@ MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t &
|
||||
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
#endif
|
||||
|
||||
bool AP_Scripting::repl_start(void) {
|
||||
if (terminal.session) { // it's already running, this is fine
|
||||
@ -197,7 +199,7 @@ bool AP_Scripting::repl_start(void) {
|
||||
if ((AP::FS().stat(REPL_DIRECTORY, &st) == -1) &&
|
||||
(AP::FS().unlink(REPL_DIRECTORY) == -1) &&
|
||||
(errno != EEXIST)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Scripting: Unable to delete old REPL %s", strerror(errno));
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: Unable to delete old REPL %s", strerror(errno));
|
||||
}
|
||||
|
||||
// create a new folder
|
||||
@ -209,7 +211,7 @@ bool AP_Scripting::repl_start(void) {
|
||||
// make the output pointer
|
||||
terminal.output_fd = AP::FS().open(REPL_OUT, O_WRONLY|O_CREAT|O_TRUNC);
|
||||
if (terminal.output_fd == -1) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Scripting: %s", "Unable to make new REPL");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: %s", "Unable to make new REPL");
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -240,14 +242,14 @@ void AP_Scripting::thread(void) {
|
||||
|
||||
lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options, terminal);
|
||||
if (lua == nullptr || !lua->heap_allocated()) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory");
|
||||
_init_failed = true;
|
||||
} else {
|
||||
// run won't return while scripting is still active
|
||||
lua->run();
|
||||
|
||||
// only reachable if the lua backend has died for any reason
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "stopped");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "stopped");
|
||||
}
|
||||
delete lua;
|
||||
lua = nullptr;
|
||||
@ -289,11 +291,11 @@ void AP_Scripting::thread(void) {
|
||||
}
|
||||
// must be enabled to get this far
|
||||
if (cleared || _restart) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted");
|
||||
break;
|
||||
}
|
||||
if ((_debug_options.get() & uint8_t(lua_scripts::DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped");
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -314,7 +316,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd
|
||||
mission_data = nullptr;
|
||||
}
|
||||
if (mission_data == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Scripting: %s", "unable to receive mission command");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: %s", "unable to receive mission command");
|
||||
return;
|
||||
}
|
||||
}
|
||||
@ -362,6 +364,7 @@ void AP_Scripting::restart_all()
|
||||
_stop = true;
|
||||
}
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
void AP_Scripting::handle_message(const mavlink_message_t &msg, const mavlink_channel_t chan) {
|
||||
if (mavlink_data.rx_buffer == nullptr) {
|
||||
return;
|
||||
@ -396,6 +399,7 @@ bool AP_Scripting::is_handling_command(uint16_t cmd_id)
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
||||
AP_Scripting *AP_Scripting::_singleton = nullptr;
|
||||
|
||||
|
@ -16,6 +16,7 @@
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
@ -43,16 +44,20 @@ public:
|
||||
bool enabled(void) const { return _enable != 0; };
|
||||
bool should_run(void) const { return enabled() && !_stop; }
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
void handle_message(const mavlink_message_t &msg, const mavlink_channel_t chan);
|
||||
|
||||
// Check if command ID is blocked
|
||||
bool is_handling_command(uint16_t cmd_id);
|
||||
#endif
|
||||
|
||||
static AP_Scripting * get_singleton(void) { return _singleton; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet);
|
||||
#endif
|
||||
|
||||
void handle_mission_command(const class AP_Mission::Mission_Command& cmd);
|
||||
|
||||
|
@ -231,6 +231,7 @@ singleton AP_Relay method toggle void uint8_t 0 AP_RELAY_NUM_RELAYS
|
||||
singleton AP_Relay method get uint8_t uint8_t 0 AP_RELAY_NUM_RELAYS
|
||||
|
||||
include GCS_MAVLink/GCS.h
|
||||
singleton GCS depends HAL_GCS_ENABLED
|
||||
singleton GCS rename gcs
|
||||
singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string
|
||||
singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t'skip_check int32_t -1 INT32_MAX
|
||||
@ -316,6 +317,7 @@ singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'e
|
||||
singleton SRV_Channels method get_emergency_stop boolean
|
||||
singleton SRV_Channels manual get_safety_state SRV_Channels_get_safety_state 0
|
||||
|
||||
ap_object RC_Channel depends AP_RC_CHANNEL_ENABLED
|
||||
ap_object RC_Channel method norm_input float
|
||||
ap_object RC_Channel method norm_input_dz float
|
||||
ap_object RC_Channel method get_aux_switch_pos uint8_t
|
||||
@ -323,6 +325,7 @@ ap_object RC_Channel method norm_input_ignore_trim float
|
||||
ap_object RC_Channel method set_override void uint16_t 0 2200 0'literal
|
||||
|
||||
include RC_Channel/RC_Channel.h
|
||||
singleton RC_Channels depends AP_RC_CHANNEL_ENABLED
|
||||
singleton RC_Channels rename rc
|
||||
singleton RC_Channels scheduler-semaphore
|
||||
singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null
|
||||
@ -444,7 +447,9 @@ singleton AP_Button depends HAL_BUTTON_ENABLED == 1
|
||||
singleton AP_Button rename button
|
||||
singleton AP_Button method get_button_state boolean uint8_t 1 AP_BUTTON_NUM_PINS
|
||||
|
||||
include AP_Notify/ScriptingLED.h
|
||||
include AP_Notify/ScriptingLED.h depends AP_NOTIFY_SCRIPTING_LED_ENABLED
|
||||
include AP_Notify/AP_Notify_config.h
|
||||
singleton ScriptingLED depends AP_NOTIFY_SCRIPTING_LED_ENABLED
|
||||
singleton ScriptingLED rename LED
|
||||
singleton ScriptingLED method get_rgb void uint8_t'Ref uint8_t'Ref uint8_t'Ref
|
||||
|
||||
@ -715,6 +720,7 @@ singleton AP_EFI method get_state void EFI_State'Ref
|
||||
-- ----END EFI Library----
|
||||
|
||||
include AP_Logger/AP_Logger.h
|
||||
singleton AP_Logger depends HAL_LOGGING_ENABLED
|
||||
singleton AP_Logger rename logger
|
||||
singleton AP_Logger manual write AP_Logger_Write 7
|
||||
singleton AP_Logger method log_file_content void string
|
||||
@ -748,6 +754,7 @@ userdata uint32_t manual tofloat uint32_t_tofloat 0
|
||||
global manual dirlist lua_dirlist 1
|
||||
global manual remove lua_removefile 1
|
||||
|
||||
singleton mavlink depends HAL_GCS_ENABLED
|
||||
singleton mavlink manual init lua_mavlink_init 2
|
||||
singleton mavlink manual register_rx_msgid lua_mavlink_register_rx_msgid 1
|
||||
singleton mavlink manual send_chan lua_mavlink_send_chan 3
|
||||
|
@ -43,6 +43,7 @@ int lua_micros(lua_State *L) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
int lua_mavlink_init(lua_State *L) {
|
||||
|
||||
// Allow : and . access
|
||||
@ -212,6 +213,7 @@ int lua_mavlink_block_command(lua_State *L) {
|
||||
lua_pushboolean(L, true);
|
||||
return 1;
|
||||
}
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
||||
int lua_mission_receive(lua_State *L) {
|
||||
binding_argcheck(L, 0);
|
||||
@ -241,6 +243,7 @@ int lua_mission_receive(lua_State *L) {
|
||||
return 5;
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
int AP_Logger_Write(lua_State *L) {
|
||||
AP_Logger * AP_logger = AP_Logger::get_singleton();
|
||||
if (AP_logger == nullptr) {
|
||||
@ -526,6 +529,7 @@ int AP_Logger_Write(lua_State *L) {
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
||||
int lua_get_i2c_device(lua_State *L) {
|
||||
|
||||
|
@ -127,7 +127,7 @@ int lua_scripts::atpanic(lua_State *L) {
|
||||
void lua_scripts::update_stats(const char *name, uint32_t run_time, int total_mem, int run_mem)
|
||||
{
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d",
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d",
|
||||
(unsigned int)run_time,
|
||||
(int)total_mem,
|
||||
(int)run_mem);
|
||||
@ -238,7 +238,7 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) {
|
||||
|
||||
auto *d = AP::FS().opendir(dirname);
|
||||
if (d == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Lua: open directory (%s) failed", dirname);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Lua: open directory (%s) failed", dirname);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -450,7 +450,7 @@ void lua_scripts::run(void) {
|
||||
bool succeeded_initial_load = false;
|
||||
|
||||
if (!_heap.available()) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Lua: Unable to allocate a heap");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Lua: Unable to allocate a heap");
|
||||
return;
|
||||
}
|
||||
|
||||
@ -475,7 +475,7 @@ void lua_scripts::run(void) {
|
||||
lua_state = lua_newstate(alloc, NULL);
|
||||
lua_State *L = lua_state;
|
||||
if (L == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Couldn't allocate a lua state");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Lua: Couldn't allocate a lua state");
|
||||
return;
|
||||
}
|
||||
|
||||
@ -504,7 +504,7 @@ void lua_scripts::run(void) {
|
||||
loaded = true;
|
||||
}
|
||||
if (!loaded) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: All directory's disabled see SCR_DIR_DISABLE");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Lua: All directory's disabled see SCR_DIR_DISABLE");
|
||||
}
|
||||
|
||||
#ifndef __clang_analyzer__
|
||||
@ -543,7 +543,7 @@ void lua_scripts::run(void) {
|
||||
}
|
||||
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name);
|
||||
}
|
||||
// copy name for logging, cant do it after as script reschedule moves the pointers
|
||||
const char * script_name = scripts->name;
|
||||
@ -572,7 +572,7 @@ void lua_scripts::run(void) {
|
||||
|
||||
} else {
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: No scripts to run");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: No scripts to run");
|
||||
}
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user