mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: improve object allocation efficiency
Make new_X return the new object instead of having to grab it to configure it. Saves ~1.3K.
This commit is contained in:
parent
3e05cd9729
commit
212256731f
|
@ -1302,12 +1302,12 @@ void emit_userdata_allocators(void) {
|
|||
while (node) {
|
||||
start_dependency(source, node->dependency);
|
||||
// New method used internally
|
||||
fprintf(source, "int new_%s(lua_State *L) {\n", node->sanatized_name);
|
||||
fprintf(source, "%s * new_%s(lua_State *L) {\n", node->name, node->sanatized_name);
|
||||
fprintf(source, " void *ud = lua_newuserdata(L, sizeof(%s));\n", node->name);
|
||||
fprintf(source, " new (ud) %s();\n", node->name);
|
||||
fprintf(source, " luaL_getmetatable(L, \"%s\");\n", node->rename ? node->rename : node->name);
|
||||
fprintf(source, " lua_setmetatable(L, -2);\n");
|
||||
fprintf(source, " return 1;\n");
|
||||
fprintf(source, " return (%s *)ud;\n", node->name);
|
||||
fprintf(source, "}\n");
|
||||
|
||||
// New method used externally, includes argcheck, overridden by custom creation function if provided
|
||||
|
@ -1321,7 +1321,8 @@ void emit_userdata_allocators(void) {
|
|||
fprintf(source, " warned = true;\n");
|
||||
fprintf(source, " }\n");
|
||||
|
||||
fprintf(source, " return new_%s(L);\n", node->sanatized_name);
|
||||
fprintf(source, " new_%s(L);\n", node->sanatized_name);
|
||||
fprintf(source, " return 1;\n");
|
||||
fprintf(source, "}\n");
|
||||
}
|
||||
|
||||
|
@ -1335,8 +1336,8 @@ void emit_ap_object_allocators(void) {
|
|||
struct userdata * node = parsed_ap_objects;
|
||||
while (node) {
|
||||
start_dependency(source, node->dependency);
|
||||
fprintf(source, "int new_%s(lua_State *L) {\n", node->sanatized_name);
|
||||
fprintf(source, " return new_ap_object(L, sizeof(%s *), \"%s\");\n", node->name, node->name);
|
||||
fprintf(source, "%s ** new_%s(lua_State *L) {\n", node->name, node->sanatized_name);
|
||||
fprintf(source, " return (%s **)new_ap_object(L, sizeof(%s *), \"%s\");\n", node->name, node->name, node->name);
|
||||
fprintf(source, "}\n");
|
||||
end_dependency(source, node->dependency);
|
||||
fprintf(source, "\n");
|
||||
|
@ -1349,8 +1350,7 @@ void emit_userdata_checkers(void) {
|
|||
while (node) {
|
||||
start_dependency(source, node->dependency);
|
||||
fprintf(source, "%s * check_%s(lua_State *L, int arg) {\n", node->name, node->sanatized_name);
|
||||
fprintf(source, " void *data = luaL_checkudata(L, arg, \"%s\");\n", node->rename ? node->rename : node->name);
|
||||
fprintf(source, " return (%s *)data;\n", node->name);
|
||||
fprintf(source, " return (%s *)luaL_checkudata(L, arg, \"%s\");\n", node->name, node->rename ? node->rename : node->name);
|
||||
fprintf(source, "}\n");
|
||||
end_dependency(source, node->dependency);
|
||||
fprintf(source, "\n");
|
||||
|
@ -1401,7 +1401,7 @@ void emit_userdata_declarations(void) {
|
|||
struct userdata * node = parsed_userdata;
|
||||
while (node) {
|
||||
start_dependency(header, node->dependency);
|
||||
fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name);
|
||||
fprintf(header, "%s * new_%s(lua_State *L);\n", node->name, node->sanatized_name);
|
||||
if (node->creation == NULL) {
|
||||
fprintf(header, "int lua_new_%s(lua_State *L);\n", node->sanatized_name);
|
||||
}
|
||||
|
@ -1415,7 +1415,7 @@ void emit_ap_object_declarations(void) {
|
|||
struct userdata * node = parsed_ap_objects;
|
||||
while (node) {
|
||||
start_dependency(header, node->dependency);
|
||||
fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name);
|
||||
fprintf(header, "%s ** new_%s(lua_State *L);\n", node->name, node->sanatized_name);
|
||||
fprintf(header, "%s ** check_%s(lua_State *L, int arg);\n", node->name, node->sanatized_name);
|
||||
end_dependency(header, node->dependency);
|
||||
node = node->next;
|
||||
|
@ -1741,8 +1741,7 @@ void emit_field(const struct userdata_field *field, const char* object_name, con
|
|||
fprintf(source, "%slua_pushinteger(L, static_cast<int32_t>(%s%s%s%s));\n", indent, object_name, object_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_UINT32_T:
|
||||
fprintf(source, "%snew_uint32_t(L);\n", indent);
|
||||
fprintf(source, "%s*check_uint32_t(L, -1) = %s%s%s%s;\n", indent, object_name, object_access, field->name, index_string);
|
||||
fprintf(source, "%s*new_uint32_t(L) = %s%s%s%s;\n", indent, object_name, object_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
error(ERROR_INTERNAL, "Can't access a NONE field");
|
||||
|
@ -1754,9 +1753,7 @@ void emit_field(const struct userdata_field *field, const char* object_name, con
|
|||
fprintf(source, "%slua_pushstring(L, %s%s%s%s);\n", indent, object_name, object_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_USERDATA:
|
||||
// userdatas must allocate a new container to return
|
||||
fprintf(source, "%snew_%s(L);\n", indent, field->type.data.ud.sanatized_name);
|
||||
fprintf(source, "%s*check_%s(L, -1) = %s%s%s%s;\n", indent, field->type.data.ud.sanatized_name, object_name, object_access, field->name, index_string);
|
||||
fprintf(source, "%s*new_%s(L) = %s%s%s%s;\n", indent, field->type.data.ud.sanatized_name, object_name, object_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_AP_OBJECT: // FIXME: collapse the identical cases here, and use the type string function
|
||||
error(ERROR_USERDATA, "AP_Object does not currently support access to userdata field's");
|
||||
|
@ -1873,16 +1870,13 @@ int emit_references(const struct argument *arg, const char * tab) {
|
|||
fprintf(source, "%slua_pushinteger(L, data_%d);\n", tab, arg_index);
|
||||
break;
|
||||
case TYPE_UINT32_T:
|
||||
fprintf(source, "%snew_uint32_t(L);\n", tab);
|
||||
fprintf(source, "%s*check_uint32_t(L, -1) = data_%d;\n", tab, arg_index);
|
||||
fprintf(source, "%s*new_uint32_t(L) = data_%d;\n", tab, arg_index);
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
fprintf(source, "%slua_pushstring(L, data_%d);\n", tab, arg_index);
|
||||
break;
|
||||
case TYPE_USERDATA:
|
||||
// userdatas must allocate a new container to return
|
||||
fprintf(source, "%snew_%s(L);\n", tab, arg->type.data.ud.sanatized_name);
|
||||
fprintf(source, "%s*check_%s(L, -1) = data_%d;\n", tab, arg->type.data.ud.sanatized_name, arg_index);
|
||||
fprintf(source, "%s*new_%s(L) = data_%d;\n", tab, arg->type.data.ud.sanatized_name, arg_index);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
error(ERROR_INTERNAL, "Attempted to emit a nullable or reference argument of type none");
|
||||
|
@ -2148,23 +2142,19 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
|||
fprintf(source, " lua_pushinteger(L, data);\n");
|
||||
break;
|
||||
case TYPE_UINT32_T:
|
||||
fprintf(source, " new_uint32_t(L);\n");
|
||||
fprintf(source, " *static_cast<uint32_t *>(luaL_checkudata(L, -1, \"uint32_t\")) = data;\n");
|
||||
fprintf(source, " *new_uint32_t(L) = data;\n");
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
fprintf(source, " lua_pushstring(L, data);\n");
|
||||
break;
|
||||
case TYPE_USERDATA:
|
||||
// userdatas must allocate a new container to return
|
||||
fprintf(source, " new_%s(L);\n", method->return_type.data.ud.sanatized_name);
|
||||
fprintf(source, " *check_%s(L, -1) = data;\n", method->return_type.data.ud.sanatized_name);
|
||||
fprintf(source, " *new_%s(L) = data;\n", method->return_type.data.ud.sanatized_name);
|
||||
break;
|
||||
case TYPE_AP_OBJECT:
|
||||
fprintf(source, " if (data == NULL) {\n");
|
||||
fprintf(source, " return 0;\n");
|
||||
fprintf(source, " }\n");
|
||||
fprintf(source, " new_%s(L);\n", method->return_type.data.ud.sanatized_name);
|
||||
fprintf(source, " *(%s**)luaL_checkudata(L, -1, \"%s\") = data;\n", method->return_type.data.ud.name, method->return_type.data.ud.name);
|
||||
fprintf(source, " *new_%s(L) = data;\n", method->return_type.data.ud.sanatized_name);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
case TYPE_LITERAL:
|
||||
|
@ -2351,14 +2341,12 @@ void emit_operators(struct userdata *data) {
|
|||
} else {
|
||||
// Return same type
|
||||
// create a container for the result
|
||||
fprintf(source, " new_%s(L);\n", data->sanatized_name);
|
||||
fprintf(source, " *check_%s(L, -1) = (%sud) %s (%sud2);\n", data->sanatized_name, access, op_sym, access);
|
||||
fprintf(source, " *new_%s(L) = (%sud) %s (%sud2);\n", data->sanatized_name, access, op_sym, access);
|
||||
}
|
||||
|
||||
} else {
|
||||
// Only a single value, lua pushes the same value onto the stack twice, so we still check for 2 arguments
|
||||
fprintf(source, " new_%s(L);\n", data->sanatized_name);
|
||||
fprintf(source, " *check_%s(L, -1) = %s (%sud);\n", data->sanatized_name, op_sym, access);
|
||||
fprintf(source, " *new_%s(L) = %s (%sud);\n", data->sanatized_name, op_sym, access);
|
||||
|
||||
}
|
||||
|
||||
|
@ -2717,11 +2705,11 @@ void emit_argcheck_helper(void) {
|
|||
fprintf(source, " return lua_unint32;\n");
|
||||
fprintf(source, "}\n\n");
|
||||
|
||||
fprintf(source, "int new_ap_object(lua_State *L, size_t size, const char * name) {\n");
|
||||
fprintf(source, " lua_newuserdata(L, size);\n");
|
||||
fprintf(source, "void * new_ap_object(lua_State *L, size_t size, const char * name) {\n");
|
||||
fprintf(source, " void * ud = lua_newuserdata(L, size);\n");
|
||||
fprintf(source, " luaL_getmetatable(L, name);\n");
|
||||
fprintf(source, " lua_setmetatable(L, -2);\n");
|
||||
fprintf(source, " return 1;\n");
|
||||
fprintf(source, " return ud;\n");
|
||||
fprintf(source, "}\n\n");
|
||||
|
||||
}
|
||||
|
@ -3216,7 +3204,7 @@ int main(int argc, char **argv) {
|
|||
fprintf(header, "uint16_t get_uint16_t(lua_State *L, int arg_num);\n");
|
||||
fprintf(header, "float get_number(lua_State *L, int arg_num, float min_val, float max_val);\n");
|
||||
fprintf(header, "uint32_t get_uint32(lua_State *L, int arg_num, uint32_t min_val, uint32_t max_val);\n");
|
||||
fprintf(header, "int new_ap_object(lua_State *L, size_t size, const char * name);\n");
|
||||
fprintf(header, "void * new_ap_object(lua_State *L, size_t size, const char * name);\n");
|
||||
|
||||
struct userdata * node = parsed_singletons;
|
||||
while (node) {
|
||||
|
|
|
@ -34,8 +34,7 @@ extern const AP_HAL::HAL& hal;
|
|||
int lua_millis(lua_State *L) {
|
||||
binding_argcheck(L, 0);
|
||||
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = AP_HAL::millis();
|
||||
*new_uint32_t(L) = AP_HAL::millis();
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
@ -44,8 +43,7 @@ int lua_millis(lua_State *L) {
|
|||
int lua_micros(lua_State *L) {
|
||||
binding_argcheck(L, 0);
|
||||
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = AP_HAL::micros();
|
||||
*new_uint32_t(L) = AP_HAL::micros();
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
@ -101,8 +99,7 @@ int lua_mavlink_receive_chan(lua_State *L) {
|
|||
luaL_addlstring(&b, (char *)&msg.msg, sizeof(msg.msg));
|
||||
luaL_pushresult(&b);
|
||||
lua_pushinteger(L, msg.chan);
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = msg.timestamp_ms;
|
||||
*new_uint32_t(L) = msg.timestamp_ms;
|
||||
return 3;
|
||||
} else {
|
||||
// no MAVLink to handle, just return no results
|
||||
|
@ -240,8 +237,7 @@ int lua_mission_receive(lua_State *L) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = cmd.time_ms;
|
||||
*new_uint32_t(L) = cmd.time_ms;
|
||||
|
||||
lua_pushinteger(L, cmd.p1);
|
||||
lua_pushnumber(L, cmd.content_p1);
|
||||
|
@ -606,8 +602,7 @@ int lua_get_i2c_device(lua_State *L) {
|
|||
return luaL_argerror(L, 1, "i2c device nullptr");
|
||||
}
|
||||
|
||||
new_AP_HAL__I2CDevice(L);
|
||||
*((AP_HAL::I2CDevice**)luaL_checkudata(L, -1, "AP_HAL::I2CDevice")) = scripting->_i2c_dev[scripting->num_i2c_devices]->get();
|
||||
*new_AP_HAL__I2CDevice(L) = scripting->_i2c_dev[scripting->num_i2c_devices]->get();
|
||||
|
||||
scripting->num_i2c_devices++;
|
||||
|
||||
|
@ -709,8 +704,7 @@ int lua_get_CAN_device(lua_State *L) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
new_ScriptingCANBuffer(L);
|
||||
*((ScriptingCANBuffer**)luaL_checkudata(L, -1, "ScriptingCANBuffer")) = scripting->_CAN_dev->add_buffer(buffer_len);
|
||||
*new_ScriptingCANBuffer(L) = scripting->_CAN_dev->add_buffer(buffer_len);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
@ -740,8 +734,7 @@ int lua_get_CAN_device2(lua_State *L) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
new_ScriptingCANBuffer(L);
|
||||
*((ScriptingCANBuffer**)luaL_checkudata(L, -1, "ScriptingCANBuffer")) = scripting->_CAN_dev2->add_buffer(buffer_len);
|
||||
*new_ScriptingCANBuffer(L) = scripting->_CAN_dev2->add_buffer(buffer_len);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
@ -764,8 +757,7 @@ int lua_serial_find_serial(lua_State *L) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
new_AP_Scripting_SerialAccess(L);
|
||||
AP_Scripting_SerialAccess *port = check_AP_Scripting_SerialAccess(L, -1);
|
||||
AP_Scripting_SerialAccess *port = new_AP_Scripting_SerialAccess(L);
|
||||
port->stream = driver_stream;
|
||||
#if AP_SCRIPTING_SERIALDEVICE_ENABLED
|
||||
port->is_device_port = false;
|
||||
|
@ -802,8 +794,7 @@ int lua_serial_find_simulated_device(lua_State *L) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
new_AP_Scripting_SerialAccess(L);
|
||||
AP_Scripting_SerialAccess *port = check_AP_Scripting_SerialAccess(L, -1);
|
||||
AP_Scripting_SerialAccess *port = new_AP_Scripting_SerialAccess(L);
|
||||
port->stream = device_stream;
|
||||
port->is_device_port = true;
|
||||
|
||||
|
@ -915,8 +906,7 @@ int lua_get_PWMSource(lua_State *L) {
|
|||
return luaL_argerror(L, 1, "PWMSources device nullptr");
|
||||
}
|
||||
|
||||
new_AP_HAL__PWMSource(L);
|
||||
*((AP_HAL::PWMSource**)luaL_checkudata(L, -1, "AP_HAL::PWMSource")) = scripting->_pwm_source[scripting->num_pwm_source];
|
||||
*new_AP_HAL__PWMSource(L) = scripting->_pwm_source[scripting->num_pwm_source];
|
||||
|
||||
scripting->num_pwm_source++;
|
||||
|
||||
|
@ -939,8 +929,7 @@ int lua_get_SocketAPM(lua_State *L) {
|
|||
for (uint8_t i=0; i<SCRIPTING_MAX_NUM_NET_SOCKET; i++) {
|
||||
if (scripting->_net_sockets[i] == nullptr) {
|
||||
scripting->_net_sockets[i] = sock;
|
||||
new_SocketAPM(L);
|
||||
*((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[i];
|
||||
*new_SocketAPM(L) = scripting->_net_sockets[i];
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
@ -1039,8 +1028,7 @@ int SocketAPM_accept(lua_State *L) {
|
|||
if (scripting->_net_sockets[i] == nullptr) {
|
||||
return 0;
|
||||
}
|
||||
new_SocketAPM(L);
|
||||
*((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[i];
|
||||
*new_SocketAPM(L) = scripting->_net_sockets[i];
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -79,8 +79,7 @@ int lua_new_uint32_t(lua_State *L) {
|
|||
return luaL_argerror(L, args, "too many arguments");
|
||||
}
|
||||
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = (args == 1) ? coerce_to_uint32_t(L, 1) : 0;
|
||||
*new_uint32_t(L) = (args == 1) ? coerce_to_uint32_t(L, 1) : 0;
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -110,8 +109,7 @@ int lua_new_uint64_t(lua_State *L) {
|
|||
break;
|
||||
}
|
||||
|
||||
new_uint64_t(L);
|
||||
*check_uint64_t(L, -1) = value;
|
||||
*new_uint64_t(L) = value;
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -193,12 +191,10 @@ int uint64_t_split(lua_State *L) {
|
|||
const uint64_t v = *check_uint64_t(L, 1);
|
||||
|
||||
// high
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = v >> 32;
|
||||
*new_uint32_t(L) = v >> 32;
|
||||
|
||||
// low
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = v & 0xFFFFFFFF;
|
||||
*new_uint32_t(L) = v & 0xFFFFFFFF;
|
||||
|
||||
return 2;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue