New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
AP_Scripting: add param set and get #12889
Changes from all commits
dce5bdf
04b9bca
1692295
b094bf5
236aab7
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -197,6 +197,11 @@ class AP_Param | |
uint16_t i; | ||
for (i=0; info[i].type != AP_PARAM_NONE; i++) ; | ||
_num_vars = i; | ||
|
||
if (_singleton != nullptr) { | ||
AP_HAL::panic("AP_Param must be singleton"); | ||
} | ||
_singleton = this; | ||
} | ||
|
||
// empty constructor | ||
|
@@ -281,13 +286,24 @@ class AP_Param | |
/// @param value The new value | ||
/// @return true if the variable is found | ||
static bool set_by_name(const char *name, float value); | ||
// name helper for scripting | ||
static bool set(const char *name, float value) { return set_by_name(name, value); }; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. These helpers actually shrink the build in my test. The compiler is smart enough to just point to the same implementation, and it saves us the string space in the script code. We could just rename |
||
|
||
/// gat a value by name, used by scripting | ||
/// | ||
/// @param name The full name of the variable to be found. | ||
/// @param value A refernce to the variable | ||
/// @return true if the variable is found | ||
static bool get(const char *name, float &value); | ||
|
||
/// set and save a value by name | ||
/// | ||
/// @param name The full name of the variable to be found. | ||
/// @param value The new value | ||
/// @return true if the variable is found | ||
static bool set_and_save_by_name(const char *name, float value); | ||
// name helper for scripting | ||
static bool set_and_save(const char *name, float value) { return set_and_save_by_name(name, value); }; | ||
|
||
/// Find a variable by index. | ||
/// | ||
|
@@ -479,7 +495,11 @@ class AP_Param | |
AP_HAL::BetterStream *port); | ||
#endif // AP_PARAM_KEY_DUMP | ||
|
||
static AP_Param *get_singleton() { return _singleton; } | ||
|
||
private: | ||
static AP_Param *_singleton; | ||
|
||
/// EEPROM header | ||
/// | ||
/// This structure is placed at the head of the EEPROM to indicate | ||
|
@@ -673,6 +693,10 @@ class AP_Param | |
void save_io_handler(void); | ||
}; | ||
|
||
namespace AP { | ||
AP_Param *param(); | ||
}; | ||
|
||
/// Template class for scalar variables. | ||
/// | ||
/// Objects of this type have a value, and can be treated in many ways as though they | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,54 @@ | ||
-- This script is a test of param set and get | ||
local count = 0 | ||
|
||
function update() -- this is the loop which periodically runs | ||
|
||
-- get and print all the scripting parameters | ||
local value = param:get('SCR_ENABLE') | ||
if value then | ||
gcs:send_text(6, string.format('LUA: SCR_ENABLE: %i',value)) | ||
else | ||
gcs:send_text(6, 'LUA: get SCR_ENABLE failed') | ||
end | ||
value = param:get('SCR_VM_I_COUNT') | ||
if value then | ||
gcs:send_text(6, string.format('LUA: SCR_VM_I_COUNT: %i',value)) | ||
else | ||
gcs:send_text(6, 'LUA: get SCR_VM_I_COUNT failed') | ||
end | ||
value = param:get('SCR_HEAP_SIZE') | ||
if value then | ||
gcs:send_text(6, string.format('LUA: SCR_HEAP_SIZE: %i',value)) | ||
else | ||
gcs:send_text(6, 'LUA: get SCR_HEAP_SIZE failed') | ||
end | ||
value = param:get('SCR_DEBUG_LVL') | ||
if value then | ||
gcs:send_text(6, string.format('LUA: SCR_DEBUG_LVL: %i',value)) | ||
else | ||
gcs:send_text(6, 'LUA: get SCR_DEBUG_LVL failed') | ||
end | ||
|
||
-- increment the script heap size by one | ||
local heap_size = param:get('SCR_HEAP_SIZE') | ||
if heap_size then | ||
if not(param:set('SCR_HEAP_SIZE',heap_size + 1)) then | ||
gcs:send_text(6, 'LUA: param set failed') | ||
end | ||
else | ||
gcs:send_text(6, 'LUA: get SCR_HEAP_SIZE failed') | ||
end | ||
|
||
|
||
count = count + 1; | ||
|
||
-- self terminate after 30 loops | ||
if count > 30 then | ||
gcs:send_text(0, 'LUA: goodbye, world') | ||
param:set('SCR_ENABLE',0) | ||
end | ||
|
||
return update, 1000 -- reschedules the loop | ||
end | ||
|
||
return update() -- run immediately before starting to reschedule |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
this find() call is very expensive. We need to be sure that the caller does not hold any semaphores