ardupilot/libraries/AP_Scripting/generator/description/bindings.desc

161 lines
7.7 KiB
Plaintext

-- Location stuff (this is a commented line)
include AP_Common/Location.h
userdata Location field lat int32_t read write -900000000 900000000
userdata Location field lng int32_t read write -1800000000 1800000000
userdata Location field relative_alt boolean read write
userdata Location field terrain_alt boolean read write
userdata Location field origin_alt boolean read write
userdata Location field loiter_xtrack boolean read write
userdata Location method get_distance float Location
userdata Location method offset void float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX
userdata Location method get_vector_from_origin_NEU boolean Vector3f'Null
userdata Location method get_bearing float Location
userdata Location method get_distance_NED Vector3f Location
userdata Location method get_distance_NE Vector2f Location
include AP_AHRS/AP_AHRS.h
singleton AP_AHRS alias ahrs
singleton AP_AHRS semaphore
singleton AP_AHRS method get_roll float
singleton AP_AHRS method get_pitch float
singleton AP_AHRS method get_yaw float
singleton AP_AHRS method get_position boolean Location'Null
singleton AP_AHRS method get_home Location
singleton AP_AHRS method get_gyro Vector3f
singleton AP_AHRS method get_hagl boolean float'Null
singleton AP_AHRS method wind_estimate Vector3f
singleton AP_AHRS method groundspeed_vector Vector2f
singleton AP_AHRS method get_velocity_NED boolean Vector3f'Null
singleton AP_AHRS method get_relative_position_NED_home boolean Vector3f'Null
singleton AP_AHRS method home_is_set boolean
singleton AP_AHRS method prearm_healthy boolean
include AP_Arming/AP_Arming.h
singleton AP_Arming alias arming
singleton AP_Arming method disarm boolean
singleton AP_Arming method is_armed boolean
singleton AP_Arming method arm boolean AP_Arming::Method::SCRIPTING'literal
include AP_BattMonitor/AP_BattMonitor.h
singleton AP_BattMonitor alias battery
singleton AP_BattMonitor method num_instances uint8_t
singleton AP_BattMonitor method healthy boolean uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method voltage float uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method voltage_resting_estimate float uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method current_amps boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method consumed_mah boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method consumed_wh boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method capacity_remaining_pct uint8_t uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method pack_capacity_mah int32_t uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method has_failsafed boolean
singleton AP_BattMonitor method overpower_detected boolean uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method get_temperature boolean float'Null uint8_t 0 ud->num_instances()
singleton AP_BattMonitor method get_cycle_count boolean uint8_t 0 ud->num_instances() uint16_t'Null
include AP_GPS/AP_GPS.h
singleton AP_GPS alias gps
singleton AP_GPS enum NO_GPS NO_FIX GPS_OK_FIX_2D GPS_OK_FIX_3D GPS_OK_FIX_3D_DGPS GPS_OK_FIX_3D_RTK_FLOAT GPS_OK_FIX_3D_RTK_FIXED
singleton AP_GPS method num_sensors uint8_t
singleton AP_GPS method primary_sensor uint8_t
singleton AP_GPS method status uint8_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method location Location uint8_t 0 ud->num_sensors()
singleton AP_GPS method speed_accuracy boolean uint8_t 0 ud->num_sensors() float'Null
singleton AP_GPS method horizontal_accuracy boolean uint8_t 0 ud->num_sensors() float'Null
singleton AP_GPS method vertical_accuracy boolean uint8_t 0 ud->num_sensors() float'Null
singleton AP_GPS method velocity Vector3f uint8_t 0 ud->num_sensors()
singleton AP_GPS method ground_speed float uint8_t 0 ud->num_sensors()
singleton AP_GPS method ground_course float uint8_t 0 ud->num_sensors()
singleton AP_GPS method num_sats uint8_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method time_week uint16_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method time_week_ms uint32_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method get_hdop uint16_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method get_vdop uint16_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method last_fix_time_ms uint32_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method last_message_time_ms uint32_t uint8_t 0 ud->num_sensors()
singleton AP_GPS method have_vertical_velocity boolean uint8_t 0 ud->num_sensors()
singleton AP_GPS method get_antenna_offset Vector3f uint8_t 0 ud->num_sensors()
singleton AP_GPS method first_unconfigured_gps boolean uint8_t'Null
include AP_Math/AP_Math.h
userdata Vector3f field x float read write -FLT_MAX FLT_MAX
userdata Vector3f field y float read write -FLT_MAX FLT_MAX
userdata Vector3f field z float read write -FLT_MAX FLT_MAX
userdata Vector3f method length float
userdata Vector3f method normalize void
userdata Vector3f method is_nan boolean
userdata Vector3f method is_inf boolean
userdata Vector3f method is_zero boolean
userdata Vector3f operator +
userdata Vector3f operator -
userdata Vector2f field x float read write -FLT_MAX FLT_MAX
userdata Vector2f field y float read write -FLT_MAX FLT_MAX
userdata Vector2f method length float
userdata Vector2f method normalize void
userdata Vector2f method is_nan boolean
userdata Vector2f method is_inf boolean
userdata Vector2f method is_zero boolean
userdata Vector2f operator +
userdata Vector2f operator -
include AP_Notify/AP_Notify.h
singleton AP_Notify alias notify
singleton AP_Notify method play_tune void string
singleton AP_Notify method handle_rgb void uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX
include AP_RangeFinder/AP_RangeFinder.h
singleton RangeFinder alias rangefinder
singleton RangeFinder method num_sensors uint8_t
include AP_Terrain/AP_Terrain.h
depends AP_TERRAIN_AVAILABLE 1 Scripting requires terrain to be available
singleton AP_Terrain alias terrain
singleton AP_Terrain method enabled boolean
singleton AP_Terrain enum TerrainStatusDisabled TerrainStatusUnhealthy TerrainStatusOK
singleton AP_Terrain method status uint8_t
singleton AP_Terrain method height_amsl boolean Location float'Null boolean
singleton AP_Terrain method height_terrain_difference_home boolean float'Null boolean
singleton AP_Terrain method height_above_terrain boolean float'Null boolean
include AP_Relay/AP_Relay.h
singleton AP_Relay alias relay
singleton AP_Relay method on void uint8_t 0 AP_RELAY_NUM_RELAYS
singleton AP_Relay method off void uint8_t 0 AP_RELAY_NUM_RELAYS
singleton AP_Relay method enabled boolean uint8_t 0 AP_RELAY_NUM_RELAYS
singleton AP_Relay method toggle void uint8_t 0 AP_RELAY_NUM_RELAYS
include GCS_MAVLink/GCS.h
singleton GCS alias 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 0U UINT32_MAX int32_t -1 INT32_MAX
include AP_Vehicle/AP_Vehicle.h
singleton AP_Vehicle alias vehicle
singleton AP_Vehicle method set_mode boolean uint8_t 0 UINT8_MAX ModeReason::SCRIPTING'literal
include AP_SerialLED/AP_SerialLED.h
singleton AP_SerialLED alias serialLED
singleton AP_SerialLED method set_num_LEDs boolean uint8_t 1 16 uint8_t 0 32
singleton AP_SerialLED method set_RGB void uint8_t 1 16 uint32_t 0U UINT32_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX
singleton AP_SerialLED method send void
include SRV_Channel/SRV_Channel.h
singleton SRV_Channels alias SRV_Channels
singleton SRV_Channels method find_channel boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint8_t'Null
include RC_Channel/RC_Channel.h
singleton RC_Channels alias rc
singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null