mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Scripting: fix userdata skip check
This commit is contained in:
parent
e7b1bcbd75
commit
b49ded9f8e
@ -373,8 +373,8 @@ userdata mavlink_mission_item_int_t field param1 float'skip_check read write
|
|||||||
userdata mavlink_mission_item_int_t field param2 float'skip_check read write
|
userdata mavlink_mission_item_int_t field param2 float'skip_check read write
|
||||||
userdata mavlink_mission_item_int_t field param3 float'skip_check read write
|
userdata mavlink_mission_item_int_t field param3 float'skip_check read write
|
||||||
userdata mavlink_mission_item_int_t field param4 float'skip_check read write
|
userdata mavlink_mission_item_int_t field param4 float'skip_check read write
|
||||||
userdata mavlink_mission_item_int_t field x int32_t read write'skip_check
|
userdata mavlink_mission_item_int_t field x int32_t'skip_check read write
|
||||||
userdata mavlink_mission_item_int_t field y int32_t read write'skip_check
|
userdata mavlink_mission_item_int_t field y int32_t'skip_check read write
|
||||||
userdata mavlink_mission_item_int_t field z float'skip_check read write
|
userdata mavlink_mission_item_int_t field z float'skip_check read write
|
||||||
userdata mavlink_mission_item_int_t field seq uint16_t read write 0 UINT16_MAX
|
userdata mavlink_mission_item_int_t field seq uint16_t read write 0 UINT16_MAX
|
||||||
userdata mavlink_mission_item_int_t field command uint16_t read write 0 UINT16_MAX
|
userdata mavlink_mission_item_int_t field command uint16_t read write 0 UINT16_MAX
|
||||||
@ -487,7 +487,7 @@ include AP_HAL/AP_HAL.h
|
|||||||
|
|
||||||
userdata AP_HAL::CANFrame depends HAL_MAX_CAN_PROTOCOL_DRIVERS
|
userdata AP_HAL::CANFrame depends HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||||
userdata AP_HAL::CANFrame rename CANFrame
|
userdata AP_HAL::CANFrame rename CANFrame
|
||||||
userdata AP_HAL::CANFrame field id uint32_t read write'skip_check
|
userdata AP_HAL::CANFrame field id uint32_t'skip_check read write
|
||||||
userdata AP_HAL::CANFrame field data'array int(ARRAY_SIZE(ud->data)) uint8_t read write 0 UINT8_MAX
|
userdata AP_HAL::CANFrame field data'array int(ARRAY_SIZE(ud->data)) uint8_t read write 0 UINT8_MAX
|
||||||
userdata AP_HAL::CANFrame field dlc uint8_t read write 0 int(ARRAY_SIZE(ud->data))
|
userdata AP_HAL::CANFrame field dlc uint8_t read write 0 int(ARRAY_SIZE(ud->data))
|
||||||
userdata AP_HAL::CANFrame method isExtended boolean
|
userdata AP_HAL::CANFrame method isExtended boolean
|
||||||
|
@ -494,6 +494,7 @@ unsigned int parse_access_flags(struct type * type) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
error(ERROR_UNKNOWN_KEYWORD, "Unknown access provided: %s", state.token);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
next_token();
|
next_token();
|
||||||
@ -730,11 +731,11 @@ void handle_userdata_field(struct userdata *data) {
|
|||||||
char *attribute = strchr(token, '\'');
|
char *attribute = strchr(token, '\'');
|
||||||
if (attribute != NULL) {
|
if (attribute != NULL) {
|
||||||
if (strcmp(attribute, keyword_attr_array) != 0) {
|
if (strcmp(attribute, keyword_attr_array) != 0) {
|
||||||
error(ERROR_USERDATA, "Unknown feild attribute %s for userdata %s feild %s", attribute, data->name, field_name);
|
error(ERROR_USERDATA, "Unknown field attribute %s for userdata %s field %s", attribute, data->name, field_name);
|
||||||
}
|
}
|
||||||
char * token = next_token();
|
char * token = next_token();
|
||||||
string_copy(&(field->array_len), token);
|
string_copy(&(field->array_len), token);
|
||||||
trace(TRACE_USERDATA, "userdata %s feild %s array length %s", data->name, field->name, field->array_len);
|
trace(TRACE_USERDATA, "userdata %s field %s array length %s", data->name, field->name, field->array_len);
|
||||||
}
|
}
|
||||||
|
|
||||||
parse_type(&(field->type), TYPE_RESTRICTION_NOT_NULLABLE, RANGE_CHECK_NONE);
|
parse_type(&(field->type), TYPE_RESTRICTION_NOT_NULLABLE, RANGE_CHECK_NONE);
|
||||||
@ -2515,7 +2516,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) {
|
|||||||
struct userdata_field *field = node->fields;
|
struct userdata_field *field = node->fields;
|
||||||
while(field) {
|
while(field) {
|
||||||
if (field->array_len == NULL) {
|
if (field->array_len == NULL) {
|
||||||
// single value feild
|
// single value field
|
||||||
if (field->access_flags & ACCESS_FLAG_READ) {
|
if (field->access_flags & ACCESS_FLAG_READ) {
|
||||||
fprintf(docs, "-- get field\n");
|
fprintf(docs, "-- get field\n");
|
||||||
emit_docs_type(field->type, "---@return", "\n");
|
emit_docs_type(field->type, "---@return", "\n");
|
||||||
@ -2527,7 +2528,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) {
|
|||||||
fprintf(docs, "function %s:%s(value) end\n\n", name, field->rename ? field->rename : field->name);
|
fprintf(docs, "function %s:%s(value) end\n\n", name, field->rename ? field->rename : field->name);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// array feild
|
// array field
|
||||||
if (field->access_flags & ACCESS_FLAG_READ) {
|
if (field->access_flags & ACCESS_FLAG_READ) {
|
||||||
fprintf(docs, "-- get array field\n");
|
fprintf(docs, "-- get array field\n");
|
||||||
fprintf(docs, "---@param index integer\n");
|
fprintf(docs, "---@param index integer\n");
|
||||||
|
Loading…
Reference in New Issue
Block a user