AP_Scripting: fix skip check userdata feild write

This commit is contained in:
Iampete1 2021-10-21 22:22:15 +01:00 committed by Andrew Tridgell
parent 003561ab75
commit da1fde06ad
3 changed files with 103 additions and 41 deletions

View File

@ -61,21 +61,41 @@ function motor_factor_table() end
---@return number
function motor_factor_table_ud:throttle(index) end
-- set array field
---@param index integer
---@param value number
function motor_factor_table_ud:throttle(index, value) end
-- get array field
---@param index integer
---@return number
function motor_factor_table_ud:yaw(index) end
-- set array field
---@param index integer
---@param value number
function motor_factor_table_ud:yaw(index, value) end
-- get array field
---@param index integer
---@return number
function motor_factor_table_ud:pitch(index) end
-- set array field
---@param index integer
---@param value number
function motor_factor_table_ud:pitch(index, value) end
-- get array field
---@param index integer
---@return number
function motor_factor_table_ud:roll(index) end
-- set array field
---@param index integer
---@param value number
function motor_factor_table_ud:roll(index, value) end
-- desc
---@class PWMSource_ud
@ -141,6 +161,10 @@ function mavlink_mission_item_int_t_ud:seq(value) end
---@return number
function mavlink_mission_item_int_t_ud:z() end
-- set field
---@param value number
function mavlink_mission_item_int_t_ud:z(value) end
-- get field
---@return integer
function mavlink_mission_item_int_t_ud:y() end
@ -161,18 +185,34 @@ function mavlink_mission_item_int_t_ud:x(value) end
---@return number
function mavlink_mission_item_int_t_ud:param4() end
-- set field
---@param value number
function mavlink_mission_item_int_t_ud:param4(value) end
-- get field
---@return number
function mavlink_mission_item_int_t_ud:param3() end
-- set field
---@param value number
function mavlink_mission_item_int_t_ud:param3(value) end
-- get field
---@return number
function mavlink_mission_item_int_t_ud:param2() end
-- set field
---@param value number
function mavlink_mission_item_int_t_ud:param2(value) end
-- get field
---@return number
function mavlink_mission_item_int_t_ud:param1() end
-- set field
---@param value number
function mavlink_mission_item_int_t_ud:param1(value) end
-- desc
---@class Parameter_ud
@ -212,10 +252,18 @@ function Vector2f() end
---@return number
function Vector2f_ud:y() end
-- set field
---@param value number
function Vector2f_ud:y(value) end
-- get field
---@return number
function Vector2f_ud:x() end
-- set field
---@param value number
function Vector2f_ud:x(value) end
-- desc
---@param param1 number
function Vector2f_ud:rotate(param1) end
@ -251,14 +299,26 @@ function Vector3f() end
---@return number
function Vector3f_ud:z() end
-- set field
---@param value number
function Vector3f_ud:z(value) end
-- get field
---@return number
function Vector3f_ud:y() end
-- set field
---@param value number
function Vector3f_ud:y(value) end
-- get field
---@return number
function Vector3f_ud:x() end
-- set field
---@param value number
function Vector3f_ud:x(value) end
-- desc
---@param param1 number
---@return Vector3f_ud
@ -506,7 +566,7 @@ function RC_Channel_ud:norm_input() end
periph = {}
-- desc
---@return uint32_t
---@return uint32_t_ud
function periph:get_vehicle_state() end
-- desc
@ -788,7 +848,7 @@ esc_telem = {}
-- desc
---@param param1 integer
---@return uint32_t|nil
---@return uint32_t_ud|nil
function esc_telem:get_usage_seconds(param1) end
-- desc
@ -1092,7 +1152,7 @@ function vehicle:start_takeoff(param1) end
function vehicle:get_control_output(param1) end
-- desc
---@return uint32_t
---@return uint32_t_ud
function vehicle:get_time_flying_ms() end
-- desc
@ -1151,7 +1211,7 @@ function gcs:send_named_float(name, value) end
-- set message interval for a given serial port and message id
---@param port_num integer -- serial port number
---@param msg_id uint32_t -- MAVLink message id
---@param msg_id uint32_t_ud -- MAVLink message id
---@param interval_us integer -- interval in micro seconds
---@return integer
---| '0' # Accepted
@ -1352,12 +1412,12 @@ function gps:have_vertical_velocity(param1) end
-- desc
---@param param1 integer
---@return uint32_t
---@return uint32_t_ud
function gps:last_message_time_ms(param1) end
-- desc
---@param param1 integer
---@return uint32_t
---@return uint32_t_ud
function gps:last_fix_time_ms(param1) end
-- desc
@ -1372,7 +1432,7 @@ function gps:get_hdop(param1) end
-- desc
---@param param1 integer
---@return uint32_t
---@return uint32_t_ud
function gps:time_week_ms(param1) end
-- desc

View File

@ -106,9 +106,9 @@ singleton AP_GPS method first_unconfigured_gps boolean uint8_t'Null
include AP_Math/AP_Math.h
userdata Vector3f field x float read write'skip_check
userdata Vector3f field y float read write'skip_check
userdata Vector3f field z float read write'skip_check
userdata Vector3f field x float'skip_check read write
userdata Vector3f field y float'skip_check read write
userdata Vector3f field z float'skip_check read write
userdata Vector3f method length float
userdata Vector3f method normalize void
userdata Vector3f method is_nan boolean
@ -120,8 +120,8 @@ userdata Vector3f method dot float Vector3f
userdata Vector3f method cross Vector3f Vector3f
userdata Vector3f method scale Vector3f float'skip_check
userdata Vector2f field x float read write'skip_check
userdata Vector2f field y float read write'skip_check
userdata Vector2f field x float'skip_check read write
userdata Vector2f field y float'skip_check read write
userdata Vector2f method length float
userdata Vector2f method normalize void
userdata Vector2f method is_nan boolean
@ -315,13 +315,13 @@ singleton AP_Mission method get_item boolean uint16_t 0 UINT16_MAX mavlink_missi
singleton AP_Mission method set_item boolean uint16_t 0 UINT16_MAX mavlink_mission_item_int_t
singleton AP_Mission method clear boolean
userdata mavlink_mission_item_int_t field param1 float read write'skip_check
userdata mavlink_mission_item_int_t field param2 float read write'skip_check
userdata mavlink_mission_item_int_t field param3 float read write'skip_check
userdata mavlink_mission_item_int_t field param4 float read write'skip_check
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 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 x int32_t read write -INT32_MAX INT32_MAX
userdata mavlink_mission_item_int_t field y int32_t read write -INT32_MAX INT32_MAX
userdata mavlink_mission_item_int_t field z float read write'skip_check
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 command uint16_t read write 0 UINT16_MAX
-- userdata mavlink_mission_item_int_t field target_system uint8_t read write 0 UINT8_MAX
@ -414,10 +414,10 @@ singleton AP_MotorsMatrix_Scripting_Dynamic method load_factors void AP_MotorsMa
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI()
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table alias motor_factor_table
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field roll'array AP_MOTORS_MAX_NUM_MOTORS float read write'skip_check
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field pitch'array AP_MOTORS_MAX_NUM_MOTORS float read write'skip_check
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field yaw'array AP_MOTORS_MAX_NUM_MOTORS float read write'skip_check
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field throttle'array AP_MOTORS_MAX_NUM_MOTORS float read write'skip_check
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field roll'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field pitch'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field yaw'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field throttle'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write
include AP_InertialSensor/AP_InertialSensor.h
singleton AP_InertialSensor alias ins

View File

@ -439,26 +439,28 @@ unsigned int parse_access_flags(struct type * type) {
flags |= ACCESS_FLAG_READ;
} else if (strcmp(state.token, keyword_write) == 0) {
flags |= ACCESS_FLAG_WRITE;
switch (type->type) {
case TYPE_FLOAT:
case TYPE_INT8_T:
case TYPE_INT16_T:
case TYPE_INT32_T:
case TYPE_UINT8_T:
case TYPE_UINT16_T:
case TYPE_UINT32_T:
case TYPE_ENUM:
type->range = parse_range_check(type->type);
break;
case TYPE_AP_OBJECT:
case TYPE_USERDATA:
case TYPE_BOOLEAN:
case TYPE_STRING:
case TYPE_LITERAL:
// a range check is illogical
break;
case TYPE_NONE:
error(ERROR_INTERNAL, "Can't access a NONE type");
if ((type->flags & TYPE_FLAGS_NO_RANGE_CHECK) == 0) {
switch (type->type) {
case TYPE_FLOAT:
case TYPE_INT8_T:
case TYPE_INT16_T:
case TYPE_INT32_T:
case TYPE_UINT8_T:
case TYPE_UINT16_T:
case TYPE_UINT32_T:
case TYPE_ENUM:
type->range = parse_range_check(type->type);
break;
case TYPE_AP_OBJECT:
case TYPE_USERDATA:
case TYPE_BOOLEAN:
case TYPE_STRING:
case TYPE_LITERAL:
// a range check is illogical
break;
case TYPE_NONE:
error(ERROR_INTERNAL, "Can't access a NONE type");
}
}
} else {
break;