mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-13 19:40:19 -04:00
d93aa15f2a
Using `luaL_Buffer` avoids the need for any heap allocation in the common case (count <= 512 bytes) and avoids stressing out the system heap for large reads, instead using the script heap. Zero net flash usage change.
961 lines
56 KiB
Plaintext
961 lines
56 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 alt int32_t read write (-LOCATION_ALT_MAX_M*100+1) (LOCATION_ALT_MAX_M*100-1)
|
|
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'skip_check float'skip_check
|
|
userdata Location method offset_bearing void float'skip_check float'skip_check
|
|
userdata Location method offset_bearing_and_pitch void float'skip_check float'skip_check float'skip_check
|
|
userdata Location method get_vector_from_origin_NEU boolean Vector3f'Null
|
|
userdata Location method get_vector_from_origin_NEU depends AP_AHRS_ENABLED
|
|
userdata Location method get_bearing float Location
|
|
userdata Location method get_distance_NED Vector3f Location
|
|
userdata Location method get_distance_NE Vector2f Location
|
|
userdata Location method get_alt_frame uint8_t
|
|
userdata Location method change_alt_frame boolean Location::AltFrame'enum Location::AltFrame::ABSOLUTE Location::AltFrame::ABOVE_TERRAIN
|
|
userdata Location method copy Location
|
|
|
|
include AP_AHRS/AP_AHRS.h
|
|
|
|
singleton AP_AHRS rename ahrs
|
|
singleton AP_AHRS depends AP_AHRS_ENABLED
|
|
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_location boolean Location'Null
|
|
singleton AP_AHRS method get_location alias get_position
|
|
singleton AP_AHRS method get_home Location
|
|
singleton AP_AHRS method get_gyro Vector3f
|
|
singleton AP_AHRS method get_accel Vector3f
|
|
singleton AP_AHRS method get_hagl boolean float'Null
|
|
singleton AP_AHRS method wind_estimate Vector3f
|
|
singleton AP_AHRS method wind_alignment float'skip_check float'skip_check
|
|
singleton AP_AHRS method head_wind float'skip_check
|
|
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 get_relative_position_NED_origin boolean Vector3f'Null
|
|
singleton AP_AHRS method get_relative_position_D_home void float'Ref
|
|
singleton AP_AHRS method home_is_set boolean
|
|
singleton AP_AHRS method healthy boolean
|
|
singleton AP_AHRS method airspeed_estimate boolean float'Null
|
|
singleton AP_AHRS method get_vibration Vector3f
|
|
singleton AP_AHRS method earth_to_body Vector3f Vector3f
|
|
singleton AP_AHRS method body_to_earth Vector3f Vector3f
|
|
singleton AP_AHRS method get_EAS2TAS float
|
|
singleton AP_AHRS method get_variances boolean float'Null float'Null float'Null Vector3f'Null float'Null
|
|
singleton AP_AHRS method set_posvelyaw_source_set void uint8_t 0 2
|
|
singleton AP_AHRS method get_vel_innovations_and_variances_for_source boolean uint8_t 3 6 Vector3f'Null Vector3f'Null
|
|
singleton AP_AHRS method set_home boolean Location
|
|
singleton AP_AHRS method get_origin boolean Location'Null
|
|
singleton AP_AHRS method set_origin boolean Location
|
|
singleton AP_AHRS method initialised boolean
|
|
singleton AP_AHRS method get_posvelyaw_source_set uint8_t
|
|
singleton AP_AHRS method get_quaternion boolean Quaternion'Null
|
|
|
|
include AP_Arming/AP_Arming.h
|
|
|
|
singleton AP_Arming rename arming
|
|
singleton AP_Arming depends AP_ARMING_ENABLED
|
|
singleton AP_Arming method disarm boolean AP_Arming::Method::SCRIPTING'literal
|
|
singleton AP_Arming method is_armed boolean
|
|
singleton AP_Arming method pre_arm_checks boolean false'literal
|
|
singleton AP_Arming method arm boolean AP_Arming::Method::SCRIPTING'literal
|
|
singleton AP_Arming method get_aux_auth_id boolean uint8_t'Null
|
|
singleton AP_Arming method set_aux_auth_passed void uint8_t'skip_check
|
|
singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string
|
|
|
|
include AP_BattMonitor/AP_BattMonitor.h
|
|
|
|
include AP_BattMonitor/AP_BattMonitor_Scripting.h
|
|
userdata BattMonitorScript_State depends AP_BATTERY_SCRIPTING_ENABLED
|
|
userdata BattMonitorScript_State field healthy boolean write
|
|
userdata BattMonitorScript_State field voltage float'skip_check write
|
|
userdata BattMonitorScript_State field cell_count uint8_t'skip_check write
|
|
userdata BattMonitorScript_State field capacity_remaining_pct uint8_t'skip_check write
|
|
userdata BattMonitorScript_State field cell_voltages'array int(ARRAY_SIZE(ud->cell_voltages)) uint16_t'skip_check write
|
|
userdata BattMonitorScript_State field cycle_count uint16_t'skip_check write
|
|
userdata BattMonitorScript_State field current_amps float'skip_check write
|
|
userdata BattMonitorScript_State field consumed_mah float'skip_check write
|
|
userdata BattMonitorScript_State field consumed_wh float'skip_check write
|
|
userdata BattMonitorScript_State field temperature float'skip_check write
|
|
|
|
singleton AP_BattMonitor rename battery
|
|
singleton AP_BattMonitor depends AP_BATTERY_ENABLED
|
|
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 boolean uint8_t'Null 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
|
|
singleton AP_BattMonitor method reset_remaining boolean uint8_t 0 ud->num_instances() float 0 100
|
|
singleton AP_BattMonitor method get_cell_voltage boolean uint8_t'skip_check uint8_t'skip_check float'Null
|
|
singleton AP_BattMonitor method handle_scripting boolean uint8_t'skip_check BattMonitorScript_State
|
|
singleton AP_BattMonitor method handle_scripting depends AP_BATTERY_SCRIPTING_ENABLED
|
|
|
|
include AP_GPS/AP_GPS.h
|
|
|
|
singleton AP_GPS depends (AP_GPS_ENABLED && (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_GPS)))
|
|
singleton AP_GPS rename 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
|
|
singleton AP_GPS method gps_yaw_deg boolean uint8_t 0 ud->num_sensors() float'Null float'Null uint32_t'Null
|
|
singleton AP_GPS method time_epoch_usec uint64_t uint8_t 0 ud->num_sensors()
|
|
|
|
include AP_Math/AP_Math.h
|
|
|
|
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
|
|
userdata Vector3f method is_inf boolean
|
|
userdata Vector3f method is_zero boolean
|
|
userdata Vector3f operator +
|
|
userdata Vector3f operator -
|
|
userdata Vector3f method dot float Vector3f
|
|
userdata Vector3f method cross Vector3f Vector3f
|
|
userdata Vector3f method scale Vector3f float'skip_check
|
|
userdata Vector3f method copy Vector3f
|
|
userdata Vector3f method xy Vector2f
|
|
userdata Vector3f method rotate_xy void float'skip_check
|
|
userdata Vector3f method angle float Vector3f
|
|
|
|
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
|
|
userdata Vector2f method is_inf boolean
|
|
userdata Vector2f method is_zero boolean
|
|
userdata Vector2f method angle float
|
|
userdata Vector2f method rotate void float'skip_check
|
|
userdata Vector2f operator +
|
|
userdata Vector2f operator -
|
|
userdata Vector2f method copy Vector2f
|
|
|
|
userdata Quaternion depends AP_AHRS_ENABLED
|
|
userdata Quaternion field q1 float'skip_check read write
|
|
userdata Quaternion field q2 float'skip_check read write
|
|
userdata Quaternion field q3 float'skip_check read write
|
|
userdata Quaternion field q4 float'skip_check read write
|
|
userdata Quaternion method length float
|
|
userdata Quaternion method normalize void
|
|
userdata Quaternion operator *
|
|
userdata Quaternion method get_euler_roll float
|
|
userdata Quaternion method get_euler_pitch float
|
|
userdata Quaternion method get_euler_yaw float
|
|
userdata Quaternion method from_euler void float'skip_check float'skip_check float'skip_check
|
|
userdata Quaternion method inverse Quaternion
|
|
userdata Quaternion method earth_to_body void Vector3f
|
|
userdata Quaternion method to_axis_angle void Vector3f
|
|
userdata Quaternion method from_axis_angle void Vector3f float'skip_check
|
|
userdata Quaternion method from_angular_velocity void Vector3f float'skip_check
|
|
|
|
include AP_Notify/AP_Notify.h
|
|
singleton AP_Notify rename notify
|
|
singleton AP_Notify depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_NOTIFY))
|
|
singleton AP_Notify method play_tune void string
|
|
singleton AP_Notify method handle_rgb void uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
|
singleton AP_Notify method handle_rgb_id void uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
|
singleton AP_Notify method send_text_scripting void string uint8_t'skip_check
|
|
singleton AP_Notify method send_text_scripting rename send_text
|
|
singleton AP_Notify method release_text_scripting void uint8_t'skip_check
|
|
singleton AP_Notify method release_text_scripting rename release_text
|
|
|
|
include AP_Proximity/AP_Proximity.h
|
|
include AP_Proximity/AP_Proximity_Backend.h
|
|
|
|
singleton AP_Proximity depends HAL_PROXIMITY_ENABLED == 1
|
|
ap_object AP_Proximity_Backend depends HAL_PROXIMITY_ENABLED == 1
|
|
ap_object AP_Proximity_Backend method handle_script_distance_msg boolean float'skip_check float'skip_check float'skip_check boolean
|
|
ap_object AP_Proximity_Backend method handle_script_3d_msg boolean Vector3f boolean
|
|
ap_object AP_Proximity_Backend method type uint8_t
|
|
ap_object AP_Proximity_Backend method set_distance_min_max boolean float'skip_check float'skip_check
|
|
ap_object AP_Proximity_Backend method update_virtual_boundary boolean
|
|
|
|
singleton AP_Proximity rename proximity
|
|
singleton AP_Proximity method get_status uint8_t
|
|
singleton AP_Proximity method num_sensors uint8_t
|
|
singleton AP_Proximity method get_object_count uint8_t
|
|
singleton AP_Proximity method get_closest_object boolean float'Null float'Null
|
|
singleton AP_Proximity method get_object_angle_and_distance boolean uint8_t'skip_check float'Null float'Null
|
|
singleton AP_Proximity method get_backend AP_Proximity_Backend uint8_t'skip_check
|
|
|
|
include AP_RangeFinder/AP_RangeFinder.h
|
|
include AP_RangeFinder/AP_RangeFinder_Backend.h
|
|
|
|
userdata RangeFinder::RangeFinder_State depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER))
|
|
userdata RangeFinder::RangeFinder_State rename RangeFinder_State
|
|
userdata RangeFinder::RangeFinder_State field last_reading_ms uint32_t'skip_check read write
|
|
userdata RangeFinder::RangeFinder_State field last_reading_ms rename last_reading
|
|
userdata RangeFinder::RangeFinder_State field status RangeFinder::Status'enum read write RangeFinder::Status::NotConnected RangeFinder::Status::Good
|
|
userdata RangeFinder::RangeFinder_State field range_valid_count uint8_t'skip_check read write
|
|
userdata RangeFinder::RangeFinder_State field distance_m float'skip_check read write
|
|
userdata RangeFinder::RangeFinder_State field distance_m rename distance
|
|
userdata RangeFinder::RangeFinder_State field signal_quality_pct int8_t'skip_check read write
|
|
userdata RangeFinder::RangeFinder_State field signal_quality_pct rename signal_quality
|
|
userdata RangeFinder::RangeFinder_State field voltage_mv uint16_t'skip_check read write
|
|
userdata RangeFinder::RangeFinder_State field voltage_mv rename voltage
|
|
|
|
ap_object AP_RangeFinder_Backend depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER))
|
|
ap_object AP_RangeFinder_Backend method distance float
|
|
ap_object AP_RangeFinder_Backend method signal_quality_pct float
|
|
ap_object AP_RangeFinder_Backend method signal_quality_pct rename signal_quality
|
|
ap_object AP_RangeFinder_Backend method orientation Rotation'enum
|
|
ap_object AP_RangeFinder_Backend method type uint8_t
|
|
ap_object AP_RangeFinder_Backend method status uint8_t
|
|
ap_object AP_RangeFinder_Backend manual handle_script_msg lua_range_finder_handle_script_msg 1 1
|
|
ap_object AP_RangeFinder_Backend method get_state void RangeFinder::RangeFinder_State'Ref
|
|
|
|
singleton RangeFinder depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER))
|
|
singleton RangeFinder rename rangefinder
|
|
singleton RangeFinder method num_sensors uint8_t
|
|
singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method signal_quality_pct_orient int8_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method max_distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method min_distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method ground_clearance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method status_orient uint8_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method has_data_orient boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
singleton RangeFinder method get_pos_offset_orient Vector3f Rotation'enum ROTATION_NONE ROTATION_MAX-1
|
|
|
|
singleton RangeFinder method get_backend AP_RangeFinder_Backend uint8_t'skip_check
|
|
|
|
include AP_Terrain/AP_Terrain.h
|
|
|
|
singleton AP_Terrain depends defined(AP_TERRAIN_AVAILABLE) && AP_TERRAIN_AVAILABLE == 1
|
|
singleton AP_Terrain rename 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 depends AP_RELAY_ENABLED
|
|
singleton AP_Relay rename 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
|
|
singleton AP_Relay method get uint8_t uint8_t 0 AP_RELAY_NUM_RELAYS
|
|
|
|
include GCS_MAVLink/GCS.h
|
|
singleton GCS depends HAL_GCS_ENABLED
|
|
singleton GCS rename 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'skip_check int32_t -1 INT32_MAX
|
|
singleton GCS method send_named_float void string float'skip_check
|
|
singleton GCS method frame_type MAV_TYPE'enum
|
|
singleton GCS method get_hud_throttle int16_t
|
|
singleton GCS method sysid_myggcs_last_seen_time_ms uint32_t
|
|
singleton GCS method sysid_myggcs_last_seen_time_ms rename last_seen
|
|
|
|
singleton GCS method get_high_latency_status boolean
|
|
singleton GCS method get_high_latency_status depends HAL_HIGH_LATENCY2_ENABLED == 1
|
|
|
|
singleton GCS method enable_high_latency_connections void boolean
|
|
singleton GCS method enable_high_latency_connections depends HAL_HIGH_LATENCY2_ENABLED == 1
|
|
|
|
include AP_ONVIF/AP_ONVIF.h depends ENABLE_ONVIF == 1
|
|
singleton AP_ONVIF depends ENABLE_ONVIF == 1
|
|
singleton AP_ONVIF rename onvif
|
|
singleton AP_ONVIF method start boolean string string string
|
|
singleton AP_ONVIF method set_absolutemove boolean float'skip_check float'skip_check float'skip_check
|
|
singleton AP_ONVIF method get_pan_tilt_limit_min Vector2f
|
|
singleton AP_ONVIF method get_pan_tilt_limit_max Vector2f
|
|
|
|
include AP_Vehicle/AP_Vehicle.h
|
|
singleton AP_Vehicle depends (!defined(HAL_BUILD_AP_PERIPH))
|
|
singleton AP_Vehicle rename vehicle
|
|
singleton AP_Vehicle scheduler-semaphore
|
|
singleton AP_Vehicle method set_mode boolean uint8_t'skip_check ModeReason::SCRIPTING'literal
|
|
singleton AP_Vehicle method get_mode uint8_t
|
|
singleton AP_Vehicle method get_control_mode_reason uint8_t
|
|
singleton AP_Vehicle method get_likely_flying boolean
|
|
singleton AP_Vehicle method get_time_flying_ms uint32_t
|
|
singleton AP_Vehicle method get_control_output boolean AP_Vehicle::ControlOutput'enum AP_Vehicle::ControlOutput::Roll ((uint32_t)AP_Vehicle::ControlOutput::Last_ControlOutput-1) float'Null
|
|
singleton AP_Vehicle method start_takeoff boolean float (-LOCATION_ALT_MAX_M*100+1) (LOCATION_ALT_MAX_M*100-1)
|
|
singleton AP_Vehicle method set_target_location boolean Location
|
|
singleton AP_Vehicle method get_target_location boolean Location'Null
|
|
singleton AP_Vehicle method update_target_location boolean Location Location
|
|
singleton AP_Vehicle method set_target_pos_NED boolean Vector3f boolean float -360 +360 boolean float'skip_check boolean boolean
|
|
singleton AP_Vehicle method set_target_posvel_NED boolean Vector3f Vector3f
|
|
singleton AP_Vehicle method set_target_posvelaccel_NED boolean Vector3f Vector3f Vector3f boolean float -360 +360 boolean float'skip_check boolean
|
|
singleton AP_Vehicle method set_target_velaccel_NED boolean Vector3f Vector3f boolean float -360 +360 boolean float'skip_check boolean
|
|
singleton AP_Vehicle method set_target_velocity_NED boolean Vector3f
|
|
singleton AP_Vehicle method set_target_angle_and_climbrate boolean float -180 180 float -90 90 float -360 360 float'skip_check boolean float'skip_check
|
|
singleton AP_Vehicle method get_circle_radius boolean float'Null
|
|
singleton AP_Vehicle method set_circle_rate boolean float'skip_check
|
|
singleton AP_Vehicle method set_steering_and_throttle boolean float -1 1 float -1 1
|
|
singleton AP_Vehicle method get_steering_and_throttle boolean float'Null float'Null
|
|
singleton AP_Vehicle method get_wp_distance_m boolean float'Null
|
|
singleton AP_Vehicle method get_wp_bearing_deg boolean float'Null
|
|
singleton AP_Vehicle method get_wp_crosstrack_error_m boolean float'Null
|
|
singleton AP_Vehicle method get_pan_tilt_norm boolean float'Null float'Null
|
|
singleton AP_Vehicle method nav_script_time boolean uint16_t'Null uint8_t'Null float'Null float'Null int16_t'Null int16_t'Null
|
|
singleton AP_Vehicle method nav_script_time_done void uint16_t'skip_check
|
|
singleton AP_Vehicle method set_target_throttle_rate_rpy void float -100 100 float'skip_check float'skip_check float'skip_check
|
|
singleton AP_Vehicle method set_rudder_offset void float'skip_check boolean
|
|
singleton AP_Vehicle method set_desired_turn_rate_and_speed boolean float'skip_check float'skip_check
|
|
singleton AP_Vehicle method set_desired_speed boolean float'skip_check
|
|
singleton AP_Vehicle method nav_scripting_enable boolean uint8_t'skip_check
|
|
singleton AP_Vehicle method set_velocity_match boolean Vector2f
|
|
singleton AP_Vehicle method set_land_descent_rate boolean float'skip_check
|
|
singleton AP_Vehicle method has_ekf_failsafed boolean
|
|
singleton AP_Vehicle method reboot void boolean
|
|
singleton AP_Vehicle method is_landing boolean
|
|
singleton AP_Vehicle method is_taking_off boolean
|
|
|
|
include AP_SerialLED/AP_SerialLED.h
|
|
singleton AP_SerialLED rename serialLED
|
|
singleton AP_SerialLED depends AP_SERIALLED_ENABLED
|
|
singleton AP_SerialLED method set_num_neopixel boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS
|
|
singleton AP_SerialLED method set_num_neopixel_rgb boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS
|
|
singleton AP_SerialLED method set_num_profiled boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS
|
|
singleton AP_SerialLED method set_RGB boolean uint8_t 1 16 int8_t -1 INT8_MAX uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
|
singleton AP_SerialLED method send boolean uint8_t 1 16
|
|
|
|
include SRV_Channel/SRV_Channel.h
|
|
singleton SRV_Channels depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RC_OUT))
|
|
singleton SRV_Channels rename 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
|
|
singleton SRV_Channels method set_output_pwm void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
|
singleton SRV_Channels method set_output_pwm_chan void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t'skip_check
|
|
singleton SRV_Channels method set_output_pwm_chan_timeout void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t'skip_check uint16_t'skip_check
|
|
singleton SRV_Channels method set_output_pwm_chan_timeout depends (!defined(HAL_BUILD_AP_PERIPH))
|
|
singleton SRV_Channels method set_output_scaled void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 float'skip_check
|
|
singleton SRV_Channels method get_output_pwm boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'Null
|
|
singleton SRV_Channels method get_output_scaled float SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1
|
|
singleton SRV_Channels method set_output_norm void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 float -1 1
|
|
singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
|
singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
|
singleton SRV_Channels method get_emergency_stop boolean
|
|
singleton SRV_Channels manual get_safety_state SRV_Channels_get_safety_state 0 1
|
|
|
|
ap_object RC_Channel depends AP_RC_CHANNEL_ENABLED
|
|
ap_object RC_Channel method norm_input float
|
|
ap_object RC_Channel method norm_input_dz float
|
|
ap_object RC_Channel method get_aux_switch_pos uint8_t
|
|
ap_object RC_Channel method norm_input_ignore_trim float
|
|
ap_object RC_Channel method set_override void uint16_t 0 2200 0'literal
|
|
|
|
include RC_Channel/RC_Channel.h
|
|
singleton RC_Channels depends AP_RC_CHANNEL_ENABLED
|
|
singleton RC_Channels rename rc
|
|
singleton RC_Channels scheduler-semaphore
|
|
singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null
|
|
singleton RC_Channels method find_channel_for_option RC_Channel RC_Channel::AUX_FUNC'enum 0 UINT16_MAX
|
|
singleton RC_Channels method run_aux_function boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX RC_Channel::AuxSwitchPos'enum RC_Channel::AuxSwitchPos::LOW RC_Channel::AuxSwitchPos::HIGH RC_Channel::AuxFuncTriggerSource::SCRIPTING'literal
|
|
singleton RC_Channels method has_valid_input boolean
|
|
singleton RC_Channels method lua_rc_channel RC_Channel uint8_t 1 NUM_RC_CHANNELS
|
|
singleton RC_Channels method lua_rc_channel rename get_channel
|
|
singleton RC_Channels method get_aux_cached boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX uint8_t'Null
|
|
|
|
include AP_Scripting/AP_Scripting_SerialAccess.h
|
|
-- don't let user create access objects
|
|
userdata AP_Scripting_SerialAccess creation null -1
|
|
userdata AP_Scripting_SerialAccess method begin void uint32_t 1U UINT32_MAX
|
|
userdata AP_Scripting_SerialAccess method write uint32_t uint8_t'skip_check
|
|
userdata AP_Scripting_SerialAccess method read int16_t
|
|
userdata AP_Scripting_SerialAccess manual readstring lua_serial_readstring 1 1
|
|
userdata AP_Scripting_SerialAccess method available uint32_t
|
|
userdata AP_Scripting_SerialAccess method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_RTS_DE
|
|
|
|
-- serial is not a real C++ type here, but its name never gets used in C++ as we only have manual methods
|
|
singleton serial depends HAL_GCS_ENABLED
|
|
singleton serial manual find_serial lua_serial_find_serial 1 1
|
|
|
|
include AP_Baro/AP_Baro.h
|
|
singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO))
|
|
singleton AP_Baro rename baro
|
|
singleton AP_Baro method get_pressure float
|
|
singleton AP_Baro method get_temperature float
|
|
singleton AP_Baro method get_external_temperature float
|
|
singleton AP_Baro method get_altitude float
|
|
singleton AP_Baro method healthy boolean uint8_t'skip_check
|
|
|
|
include AP_OpticalFlow/AP_OpticalFlow.h
|
|
singleton AP_OpticalFlow depends AP_OPTICALFLOW_ENABLED
|
|
singleton AP_OpticalFlow rename optical_flow
|
|
singleton AP_OpticalFlow method enabled boolean
|
|
singleton AP_OpticalFlow method healthy boolean
|
|
singleton AP_OpticalFlow method quality uint8_t
|
|
|
|
include AP_ESC_Telem/AP_ESC_Telem.h
|
|
|
|
userdata AP_ESC_Telem_Backend::TelemetryData depends (HAL_WITH_ESC_TELEM == 1)
|
|
userdata AP_ESC_Telem_Backend::TelemetryData rename ESCTelemetryData
|
|
userdata AP_ESC_Telem_Backend::TelemetryData field temperature_cdeg int16_t'skip_check write
|
|
userdata AP_ESC_Telem_Backend::TelemetryData field voltage float'skip_check write
|
|
userdata AP_ESC_Telem_Backend::TelemetryData field current float'skip_check write
|
|
userdata AP_ESC_Telem_Backend::TelemetryData field consumption_mah float'skip_check write
|
|
userdata AP_ESC_Telem_Backend::TelemetryData field motor_temp_cdeg int16_t'skip_check write
|
|
|
|
singleton AP_ESC_Telem depends HAL_WITH_ESC_TELEM == 1
|
|
singleton AP_ESC_Telem rename esc_telem
|
|
singleton AP_ESC_Telem method get_rpm boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
|
|
singleton AP_ESC_Telem method get_temperature boolean uint8_t 0 NUM_SERVO_CHANNELS int16_t'Null
|
|
singleton AP_ESC_Telem method get_motor_temperature boolean uint8_t 0 NUM_SERVO_CHANNELS int16_t'Null
|
|
singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
|
|
singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
|
|
singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
|
|
singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null
|
|
singleton AP_ESC_Telem method update_rpm void uint8_t 0 NUM_SERVO_CHANNELS uint16_t'skip_check float'skip_check
|
|
singleton AP_ESC_Telem method update_telem_data void uint8_t 0 NUM_SERVO_CHANNELS AP_ESC_Telem_Backend::TelemetryData uint16_t'skip_check
|
|
singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check
|
|
|
|
include AP_Param/AP_Param.h
|
|
singleton AP_Param rename param
|
|
singleton AP_Param method get boolean string float'Null
|
|
singleton AP_Param method set_by_name boolean string float'skip_check
|
|
singleton AP_Param method set_by_name rename set
|
|
singleton AP_Param method set_and_save_by_name boolean string float'skip_check
|
|
singleton AP_Param method set_and_save_by_name rename set_and_save
|
|
singleton AP_Param method set_default_by_name boolean string float'skip_check
|
|
singleton AP_Param method set_default_by_name rename set_default
|
|
singleton AP_Param method add_table boolean uint8_t 0 200 string uint8_t 1 63
|
|
singleton AP_Param method add_table depends AP_PARAM_DYNAMIC_ENABLED
|
|
singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string float'skip_check
|
|
singleton AP_Param method add_param depends AP_PARAM_DYNAMIC_ENABLED
|
|
|
|
include AP_Scripting/AP_Scripting_helpers.h
|
|
userdata Parameter creation lua_new_Parameter 0
|
|
userdata Parameter method init boolean string
|
|
userdata Parameter method init_by_info boolean uint16_t'skip_check uint32_t'skip_check ap_var_type'enum AP_PARAM_INT8 AP_PARAM_FLOAT
|
|
userdata Parameter method get boolean float'Null
|
|
userdata Parameter method set boolean float'skip_check
|
|
userdata Parameter method set_and_save boolean float'skip_check
|
|
userdata Parameter method configured boolean
|
|
userdata Parameter method set_default boolean float'skip_check
|
|
|
|
include AP_Scripting/AP_Scripting.h
|
|
singleton AP_Scripting rename scripting
|
|
singleton AP_Scripting method restart_all void
|
|
|
|
include AP_Mission/AP_Mission.h
|
|
singleton AP_Mission depends AP_MISSION_ENABLED
|
|
singleton AP_Mission rename mission
|
|
singleton AP_Mission scheduler-semaphore
|
|
singleton AP_Mission enum MISSION_STOPPED MISSION_RUNNING MISSION_COMPLETE
|
|
singleton AP_Mission method state uint8_t
|
|
singleton AP_Mission method get_current_nav_index uint16_t
|
|
singleton AP_Mission method set_current_cmd boolean uint16_t 0 (ud->num_commands()-1)
|
|
singleton AP_Mission method get_prev_nav_cmd_id uint16_t
|
|
singleton AP_Mission method get_current_nav_id uint16_t
|
|
singleton AP_Mission method get_current_do_cmd_id uint16_t
|
|
singleton AP_Mission method num_commands uint16_t
|
|
singleton AP_Mission method get_item boolean uint16_t'skip_check mavlink_mission_item_int_t'Null
|
|
singleton AP_Mission method set_item boolean uint16_t'skip_check mavlink_mission_item_int_t
|
|
singleton AP_Mission method clear boolean
|
|
singleton AP_Mission method cmd_has_location boolean uint16_t'skip_check
|
|
singleton AP_Mission method jump_to_tag boolean uint16_t 0 UINT16_MAX
|
|
singleton AP_Mission method get_index_of_jump_tag uint16_t uint16_t 0 UINT16_MAX
|
|
singleton AP_Mission method get_last_jump_tag boolean uint16_t'Null uint16_t'Null
|
|
singleton AP_Mission method jump_to_landing_sequence boolean
|
|
singleton AP_Mission method jump_to_abort_landing_sequence boolean
|
|
|
|
|
|
userdata mavlink_mission_item_int_t depends AP_MISSION_ENABLED
|
|
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'skip_check read write
|
|
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 seq uint16_t'skip_check read write
|
|
userdata mavlink_mission_item_int_t field command uint16_t'skip_check read write
|
|
-- userdata mavlink_mission_item_int_t field target_system uint8_t'skip_check read write
|
|
-- userdata mavlink_mission_item_int_t field target_component uint8_t'skip_check read write
|
|
userdata mavlink_mission_item_int_t field frame uint8_t'skip_check read write
|
|
userdata mavlink_mission_item_int_t field current uint8_t'skip_check read write
|
|
-- userdata mavlink_mission_item_int_t field autocontinue uint8_t'skip_check read write
|
|
|
|
|
|
include AP_RPM/AP_RPM.h
|
|
singleton AP_RPM rename RPM
|
|
singleton AP_RPM depends AP_RPM_ENABLED
|
|
singleton AP_RPM method get_rpm boolean uint8_t 0 RPM_MAX_INSTANCES float'Null
|
|
|
|
include AP_Button/AP_Button.h
|
|
singleton AP_Button depends HAL_BUTTON_ENABLED == 1
|
|
singleton AP_Button rename button
|
|
singleton AP_Button method get_button_state boolean uint8_t 1 AP_BUTTON_NUM_PINS
|
|
|
|
include AP_Notify/ScriptingLED.h depends AP_NOTIFY_SCRIPTING_LED_ENABLED
|
|
include AP_Notify/AP_Notify_config.h
|
|
singleton ScriptingLED depends AP_NOTIFY_SCRIPTING_LED_ENABLED
|
|
singleton ScriptingLED rename LED
|
|
singleton ScriptingLED method get_rgb void uint8_t'Ref uint8_t'Ref uint8_t'Ref
|
|
|
|
include ../ArduPlane/quadplane.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
|
singleton QuadPlane rename quadplane
|
|
singleton QuadPlane depends APM_BUILD_TYPE(APM_BUILD_ArduPlane) && HAL_QUADPLANE_ENABLED
|
|
singleton QuadPlane method in_vtol_mode boolean
|
|
singleton QuadPlane method in_assisted_flight boolean
|
|
singleton QuadPlane method abort_landing boolean
|
|
singleton QuadPlane method in_vtol_land_descent boolean
|
|
|
|
include ../ArduSub/Sub.h depends APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
|
singleton Sub rename sub
|
|
singleton Sub depends APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
|
singleton Sub method get_and_clear_button_count uint8_t uint8_t 1 4
|
|
singleton Sub method is_button_pressed boolean uint8_t 1 4
|
|
singleton Sub method rangefinder_alt_ok boolean
|
|
singleton Sub method get_rangefinder_target_cm float
|
|
singleton Sub method set_rangefinder_target_cm boolean float'skip_check
|
|
|
|
include AP_Motors/AP_MotorsMatrix.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AP_MotorsMatrix depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AP_MotorsMatrix rename MotorsMatrix
|
|
singleton AP_MotorsMatrix method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
|
singleton AP_MotorsMatrix method add_motor_raw void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float'skip_check float'skip_check float'skip_check uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
|
singleton AP_MotorsMatrix method set_throttle_factor boolean int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float 0 FLT_MAX
|
|
singleton AP_MotorsMatrix method get_lost_motor uint8_t
|
|
singleton AP_MotorsMatrix method get_thrust_boost boolean
|
|
|
|
include AP_Frsky_Telem/AP_Frsky_SPort.h
|
|
singleton AP_Frsky_SPort rename frsky_sport
|
|
singleton AP_Frsky_SPort depends AP_FRSKY_SPORT_TELEM_ENABLED
|
|
singleton AP_Frsky_SPort method sport_telemetry_push boolean uint8_t'skip_check uint8_t'skip_check uint16_t'skip_check int32_t'skip_check
|
|
singleton AP_Frsky_SPort method prep_number uint16_t int32_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
|
|
|
include AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h depends APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
|
singleton AC_AttitudeControl_Multi_6DoF depends APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
|
singleton AC_AttitudeControl_Multi_6DoF rename attitude_control
|
|
singleton AC_AttitudeControl_Multi_6DoF method set_lateral_enable void boolean
|
|
singleton AC_AttitudeControl_Multi_6DoF method set_forward_enable void boolean
|
|
singleton AC_AttitudeControl_Multi_6DoF method set_offset_roll_pitch void float'skip_check float'skip_check
|
|
|
|
|
|
include AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h depends APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
|
singleton AP_MotorsMatrix_6DoF_Scripting depends APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
|
singleton AP_MotorsMatrix_6DoF_Scripting rename Motors_6DoF
|
|
singleton AP_MotorsMatrix_6DoF_Scripting method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
|
singleton AP_MotorsMatrix_6DoF_Scripting method add_motor void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float'skip_check float'skip_check float'skip_check float'skip_check float'skip_check float'skip_check boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
|
|
|
include AP_HAL/I2CDevice.h
|
|
ap_object AP_HAL::I2CDevice semaphore-pointer
|
|
ap_object AP_HAL::I2CDevice method set_retries void uint8_t 0 20
|
|
ap_object AP_HAL::I2CDevice method write_register boolean uint8_t'skip_check uint8_t'skip_check
|
|
ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers 2 1
|
|
ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check
|
|
|
|
include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1)
|
|
global manual Socket lua_get_SocketAPM 1 1 depends (AP_NETWORKING_ENABLED==1)
|
|
|
|
ap_object SocketAPM depends (AP_NETWORKING_ENABLED==1)
|
|
ap_object SocketAPM method connect boolean string uint16_t'skip_check
|
|
ap_object SocketAPM method bind boolean string uint16_t'skip_check
|
|
ap_object SocketAPM method send int32_t string uint32_t'skip_check
|
|
ap_object SocketAPM method listen boolean uint8_t'skip_check
|
|
ap_object SocketAPM method set_blocking boolean boolean
|
|
ap_object SocketAPM method is_connected boolean
|
|
ap_object SocketAPM method pollout boolean uint32_t'skip_check
|
|
ap_object SocketAPM method pollin boolean uint32_t'skip_check
|
|
ap_object SocketAPM method reuseaddress boolean
|
|
ap_object SocketAPM manual sendfile SocketAPM_sendfile 1 1
|
|
ap_object SocketAPM manual close SocketAPM_close 0 0
|
|
ap_object SocketAPM manual recv SocketAPM_recv 1 1
|
|
ap_object SocketAPM manual accept SocketAPM_accept 0 1
|
|
|
|
ap_object AP_HAL::AnalogSource depends !defined(HAL_DISABLE_ADC_DRIVER)
|
|
ap_object AP_HAL::AnalogSource method set_pin boolean uint8_t'skip_check
|
|
ap_object AP_HAL::AnalogSource method voltage_average float
|
|
ap_object AP_HAL::AnalogSource method voltage_latest float
|
|
ap_object AP_HAL::AnalogSource method voltage_average_ratiometric float
|
|
|
|
global manual PWMSource lua_get_PWMSource 0 1
|
|
|
|
ap_object AP_HAL::PWMSource method set_pin boolean uint8_t'skip_check "Scripting"'literal
|
|
ap_object AP_HAL::PWMSource method get_pwm_us uint16_t
|
|
ap_object AP_HAL::PWMSource method get_pwm_avg_us uint16_t
|
|
|
|
singleton hal.gpio rename gpio
|
|
singleton hal.gpio literal
|
|
singleton hal.gpio method read boolean uint8_t'skip_check
|
|
singleton hal.gpio method write void uint8_t'skip_check uint8_t 0 1
|
|
singleton hal.gpio method toggle void uint8_t'skip_check
|
|
singleton hal.gpio method pinMode void uint8_t'skip_check uint8_t 0 1
|
|
|
|
singleton hal.analogin depends !defined(HAL_DISABLE_ADC_DRIVER)
|
|
singleton hal.analogin rename analog
|
|
singleton hal.analogin literal
|
|
singleton hal.analogin method channel AP_HAL::AnalogSource ANALOG_INPUT_NONE'literal
|
|
singleton hal.analogin method mcu_temperature float
|
|
singleton hal.analogin method mcu_temperature depends HAL_WITH_MCU_MONITORING
|
|
|
|
include AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AP_MotorsMatrix_Scripting_Dynamic depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AP_MotorsMatrix_Scripting_Dynamic rename Motors_dynamic
|
|
singleton AP_MotorsMatrix_Scripting_Dynamic method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
|
singleton AP_MotorsMatrix_Scripting_Dynamic method add_motor void uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
|
singleton AP_MotorsMatrix_Scripting_Dynamic method load_factors void AP_MotorsMatrix_Scripting_Dynamic::factor_table
|
|
|
|
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 rename motor_factor_table
|
|
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 depends AP_INERTIALSENSOR_ENABLED
|
|
singleton AP_InertialSensor rename ins
|
|
singleton AP_InertialSensor method get_temperature float uint8_t 0 INS_MAX_INSTANCES
|
|
singleton AP_InertialSensor method get_gyro_health boolean uint8_t'skip_check
|
|
singleton AP_InertialSensor method accels_consistent boolean float'skip_check
|
|
singleton AP_InertialSensor method get_accel_health boolean uint8_t'skip_check
|
|
singleton AP_InertialSensor method calibrating boolean
|
|
singleton AP_InertialSensor method get_gyro Vector3f uint8_t'skip_check
|
|
singleton AP_InertialSensor method get_accel Vector3f uint8_t'skip_check
|
|
singleton AP_InertialSensor method gyros_consistent boolean uint8_t'skip_check
|
|
|
|
singleton CAN manual get_device lua_get_CAN_device 1 1
|
|
singleton CAN manual get_device2 lua_get_CAN_device2 1 1
|
|
singleton CAN depends AP_SCRIPTING_CAN_SENSOR_ENABLED
|
|
|
|
include AP_Scripting/AP_Scripting_CANSensor.h
|
|
include AP_HAL/AP_HAL.h
|
|
|
|
userdata AP_HAL::CANFrame depends AP_SCRIPTING_CAN_SENSOR_ENABLED
|
|
userdata AP_HAL::CANFrame rename CANFrame
|
|
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'skip_check read write
|
|
userdata AP_HAL::CANFrame field dlc uint8_t read write 0 int(ARRAY_SIZE(ud->data))
|
|
userdata AP_HAL::CANFrame method id_signed int32_t
|
|
userdata AP_HAL::CANFrame method isExtended boolean
|
|
userdata AP_HAL::CANFrame method isRemoteTransmissionRequest boolean
|
|
userdata AP_HAL::CANFrame method isErrorFrame boolean
|
|
|
|
ap_object ScriptingCANBuffer depends AP_SCRIPTING_CAN_SENSOR_ENABLED
|
|
ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_t'skip_check
|
|
ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null
|
|
ap_object ScriptingCANBuffer method add_filter boolean uint32_t'skip_check uint32_t'skip_check
|
|
|
|
include ../Tools/AP_Periph/AP_Periph.h depends defined(HAL_BUILD_AP_PERIPH)
|
|
singleton AP_Periph_FW depends defined(HAL_BUILD_AP_PERIPH)
|
|
singleton AP_Periph_FW rename periph
|
|
singleton AP_Periph_FW method get_yaw_earth float
|
|
singleton AP_Periph_FW method get_vehicle_state uint32_t
|
|
singleton AP_Periph_FW method can_printf void "%s"'literal string
|
|
singleton AP_Periph_FW method reboot void boolean
|
|
|
|
include AP_Motors/AP_Motors_Class.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AP::motors() depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AP::motors() literal
|
|
singleton AP::motors() rename motors
|
|
singleton AP::motors() method set_frame_string void string
|
|
singleton AP::motors() method get_interlock boolean
|
|
singleton AP::motors() method get_desired_spool_state uint8_t
|
|
singleton AP::motors() method get_roll float
|
|
singleton AP::motors() method get_roll_ff float
|
|
singleton AP::motors() method get_pitch float
|
|
singleton AP::motors() method get_pitch_ff float
|
|
singleton AP::motors() method get_yaw float
|
|
singleton AP::motors() method get_yaw_ff float
|
|
singleton AP::motors() method get_throttle float
|
|
singleton AP::motors() method get_forward float
|
|
singleton AP::motors() method get_lateral float
|
|
singleton AP::motors() method get_spool_state uint8_t
|
|
singleton AP::motors() method set_external_limits void boolean boolean boolean boolean boolean
|
|
|
|
include AP_Common/AP_FWVersion.h
|
|
singleton AP::fwversion() literal
|
|
singleton AP::fwversion() reference
|
|
singleton AP::fwversion() rename FWVersion
|
|
singleton AP::fwversion() field fw_short_string string read
|
|
singleton AP::fwversion() field fw_short_string rename string
|
|
singleton AP::fwversion() field vehicle_type uint8_t read
|
|
singleton AP::fwversion() field vehicle_type rename type
|
|
singleton AP::fwversion() field major uint8_t read
|
|
singleton AP::fwversion() field minor uint8_t read
|
|
singleton AP::fwversion() field patch uint8_t read
|
|
singleton AP::fwversion() field fw_hash_str string read
|
|
singleton AP::fwversion() field fw_hash_str rename hash
|
|
|
|
include AP_Follow/AP_Follow.h
|
|
singleton AP_Follow depends AP_FOLLOW_ENABLED && (APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI)
|
|
singleton AP_Follow rename follow
|
|
singleton AP_Follow method have_target boolean
|
|
singleton AP_Follow method get_last_update_ms uint32_t
|
|
singleton AP_Follow method get_target_location_and_velocity boolean Location'Null Vector3f'Null
|
|
singleton AP_Follow method get_target_location_and_velocity_ofs boolean Location'Null Vector3f'Null
|
|
singleton AP_Follow method get_target_heading_deg boolean float'Null
|
|
|
|
include AC_PrecLand/AC_PrecLand.h
|
|
singleton AC_PrecLand depends AC_PRECLAND_ENABLED && (APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI)
|
|
singleton AC_PrecLand rename precland
|
|
singleton AC_PrecLand method healthy boolean
|
|
singleton AC_PrecLand method target_acquired boolean
|
|
singleton AC_PrecLand method get_last_valid_target_ms uint32_t
|
|
singleton AC_PrecLand method get_target_velocity boolean Vector2f'Null
|
|
singleton AC_PrecLand method get_target_location boolean Location'Null
|
|
|
|
include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AC_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
|
singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref
|
|
|
|
include APM_Control/AR_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
singleton AR_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
singleton AR_AttitudeControl method get_srate void float'Ref float'Ref
|
|
|
|
include APM_Control/AR_PosControl.h depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
singleton AR_PosControl depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
|
singleton AR_PosControl method get_srate void float'Ref
|
|
|
|
include AP_Mount/AP_Mount.h
|
|
singleton AP_Mount depends HAL_MOUNT_ENABLED == 1
|
|
singleton AP_Mount rename mount
|
|
singleton AP_Mount method get_mode MAV_MOUNT_MODE'enum uint8_t'skip_check
|
|
singleton AP_Mount method set_mode void uint8_t'skip_check MAV_MOUNT_MODE'enum MAV_MOUNT_MODE_RETRACT MAV_MOUNT_MODE_HOME_LOCATION
|
|
singleton AP_Mount method set_angle_target void uint8_t'skip_check float'skip_check float'skip_check float'skip_check boolean
|
|
singleton AP_Mount method set_rate_target void uint8_t'skip_check float'skip_check float'skip_check float'skip_check boolean
|
|
singleton AP_Mount method set_roi_target void uint8_t'skip_check Location
|
|
singleton AP_Mount method get_attitude_euler boolean uint8_t'skip_check float'Null float'Null float'Null
|
|
singleton AP_Mount method get_rate_target boolean uint8_t'skip_check float'Null float'Null float'Null boolean'Null
|
|
singleton AP_Mount method get_angle_target boolean uint8_t'skip_check float'Null float'Null float'Null boolean'Null
|
|
singleton AP_Mount method get_location_target boolean uint8_t'skip_check Location'Null
|
|
singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check
|
|
|
|
include AP_Camera/AP_Camera.h
|
|
singleton AP_Camera depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1)
|
|
singleton AP_Camera rename camera
|
|
singleton AP_Camera semaphore
|
|
singleton AP_Camera method take_picture void uint8_t'skip_check
|
|
singleton AP_Camera method record_video boolean uint8_t'skip_check boolean
|
|
singleton AP_Camera method set_trigger_distance void uint8_t'skip_check float'skip_check
|
|
userdata AP_Camera::camera_state_t depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1)
|
|
userdata AP_Camera::camera_state_t field take_pic_incr uint16_t'skip_check read
|
|
userdata AP_Camera::camera_state_t field recording_video boolean read
|
|
userdata AP_Camera::camera_state_t field zoom_type uint8_t'skip_check read
|
|
userdata AP_Camera::camera_state_t field zoom_value float'skip_check read
|
|
userdata AP_Camera::camera_state_t field focus_type uint8_t'skip_check read
|
|
userdata AP_Camera::camera_state_t field focus_value float'skip_check read
|
|
userdata AP_Camera::camera_state_t field tracking_type uint8_t'skip_check read
|
|
userdata AP_Camera::camera_state_t field tracking_p1 Vector2f read
|
|
userdata AP_Camera::camera_state_t field tracking_p2 Vector2f read
|
|
singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camera_state_t'Null
|
|
|
|
include AP_Winch/AP_Winch.h
|
|
singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI
|
|
singleton AP_Winch rename winch
|
|
singleton AP_Winch method healthy boolean
|
|
singleton AP_Winch method relax void
|
|
singleton AP_Winch method release_length void float'skip_check
|
|
singleton AP_Winch method set_desired_rate void float'skip_check
|
|
singleton AP_Winch method get_rate_max float
|
|
|
|
include AP_IOMCU/AP_IOMCU.h
|
|
singleton AP_IOMCU depends HAL_WITH_IO_MCU
|
|
singleton AP_IOMCU rename iomcu
|
|
singleton AP_IOMCU method healthy boolean
|
|
|
|
include AP_Compass/AP_Compass.h
|
|
singleton Compass rename compass
|
|
singleton Compass depends AP_COMPASS_ENABLED
|
|
singleton Compass method healthy boolean uint8_t'skip_check
|
|
|
|
-- ----EFI Library----
|
|
include AP_EFI/AP_EFI.h depends HAL_EFI_ENABLED
|
|
include AP_EFI/AP_EFI_Scripting.h depends AP_EFI_SCRIPTING_ENABLED
|
|
include AP_EFI/AP_EFI_config.h
|
|
|
|
userdata Cylinder_Status depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
|
userdata Cylinder_Status field ignition_timing_deg float'skip_check read write
|
|
userdata Cylinder_Status field injection_time_ms float'skip_check read write
|
|
userdata Cylinder_Status field cylinder_head_temperature float'skip_check read write
|
|
userdata Cylinder_Status field cylinder_head_temperature2 float'skip_check read write
|
|
userdata Cylinder_Status field exhaust_gas_temperature float'skip_check read write
|
|
userdata Cylinder_Status field exhaust_gas_temperature2 float'skip_check read write
|
|
userdata Cylinder_Status field lambda_coefficient float'skip_check read write
|
|
|
|
userdata EFI_State depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
|
userdata EFI_State field last_updated_ms uint32_t'skip_check read write
|
|
userdata EFI_State field general_error boolean read write
|
|
userdata EFI_State field engine_load_percent uint8_t'skip_check read write
|
|
userdata EFI_State field engine_speed_rpm uint32_t'skip_check read write
|
|
userdata EFI_State field spark_dwell_time_ms float'skip_check read write
|
|
userdata EFI_State field atmospheric_pressure_kpa float'skip_check read write
|
|
userdata EFI_State field intake_manifold_pressure_kpa float'skip_check read write
|
|
userdata EFI_State field intake_manifold_temperature float'skip_check read write
|
|
userdata EFI_State field coolant_temperature float'skip_check read write
|
|
userdata EFI_State field oil_pressure float'skip_check read write
|
|
userdata EFI_State field oil_temperature float'skip_check read write
|
|
userdata EFI_State field fuel_pressure float'skip_check read write
|
|
userdata EFI_State field fuel_pressure_status Fuel_Pressure_Status'enum read write Fuel_Pressure_Status::NOT_SUPPORTED Fuel_Pressure_Status::ABOVE_NOMINAL
|
|
userdata EFI_State field fuel_consumption_rate_cm3pm float'skip_check read write
|
|
userdata EFI_State field estimated_consumed_fuel_volume_cm3 float'skip_check read write
|
|
userdata EFI_State field throttle_position_percent uint8_t'skip_check read write
|
|
userdata EFI_State field ecu_index uint8_t'skip_check read write
|
|
userdata EFI_State field cylinder_status Cylinder_Status read write
|
|
userdata EFI_State field ignition_voltage float'skip_check read write
|
|
userdata EFI_State field throttle_out float'skip_check read write
|
|
userdata EFI_State field pt_compensation float'skip_check read write
|
|
|
|
ap_object AP_EFI_Backend depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
|
ap_object AP_EFI_Backend method handle_scripting boolean EFI_State
|
|
|
|
singleton AP_EFI depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
|
singleton AP_EFI rename efi
|
|
singleton AP_EFI method get_backend AP_EFI_Backend uint8_t'skip_check
|
|
singleton AP_EFI method get_state void EFI_State'Ref
|
|
|
|
-- ----END EFI Library----
|
|
|
|
include AP_Logger/AP_Logger.h
|
|
singleton AP_Logger depends HAL_LOGGING_ENABLED
|
|
singleton AP_Logger rename logger
|
|
singleton AP_Logger manual write AP_Logger_Write 6 0
|
|
singleton AP_Logger method log_file_content void string
|
|
singleton AP_Logger method log_file_content depends HAL_LOGGER_FILE_CONTENTS_ENABLED
|
|
|
|
singleton i2c manual get_device lua_get_i2c_device 4 1
|
|
|
|
global manual millis lua_millis 0 1
|
|
global manual micros lua_micros 0 1
|
|
global manual mission_receive lua_mission_receive 0 5 depends AP_MISSION_ENABLED
|
|
|
|
userdata uint32_t creation lua_new_uint32_t 1
|
|
userdata uint32_t operator_getter coerce_to_uint32_t
|
|
userdata uint32_t operator +
|
|
userdata uint32_t operator -
|
|
userdata uint32_t operator *
|
|
userdata uint32_t operator /
|
|
-- We know name of the generated function so we can point at it again with a manual operator so idiv is the same as div
|
|
userdata uint32_t manual_operator __idiv uint32_t___div
|
|
userdata uint32_t operator %
|
|
userdata uint32_t operator &
|
|
userdata uint32_t operator |
|
|
userdata uint32_t operator ^
|
|
userdata uint32_t operator <<
|
|
userdata uint32_t operator >>
|
|
userdata uint32_t operator ==
|
|
userdata uint32_t operator <
|
|
userdata uint32_t operator <=
|
|
userdata uint32_t operator ~
|
|
userdata uint32_t manual_operator __tostring uint32_t___tostring
|
|
userdata uint32_t manual toint uint32_t_toint 0 1
|
|
userdata uint32_t manual tofloat uint32_t_tofloat 0 1
|
|
|
|
userdata uint64_t creation lua_new_uint64_t 2
|
|
userdata uint64_t operator_getter coerce_to_uint64_t
|
|
userdata uint64_t operator +
|
|
userdata uint64_t operator -
|
|
userdata uint64_t operator *
|
|
userdata uint64_t operator /
|
|
userdata uint64_t operator %
|
|
userdata uint64_t operator &
|
|
userdata uint64_t operator |
|
|
userdata uint64_t operator ^
|
|
userdata uint64_t operator <<
|
|
userdata uint64_t operator >>
|
|
userdata uint64_t operator ==
|
|
userdata uint64_t operator <
|
|
userdata uint64_t operator <=
|
|
userdata uint64_t operator ~
|
|
userdata uint64_t manual_operator __tostring uint64_t___tostring
|
|
userdata uint64_t manual toint uint64_t_toint 0 1
|
|
userdata uint64_t manual tofloat uint64_t_tofloat 0 1
|
|
userdata uint64_t manual split uint64_t_split 0 2
|
|
|
|
global manual dirlist lua_dirlist 1 2
|
|
global manual remove lua_removefile 1 3
|
|
global manual print lua_print 1 0
|
|
|
|
singleton mavlink depends HAL_GCS_ENABLED
|
|
singleton mavlink manual init lua_mavlink_init 2 0
|
|
singleton mavlink manual register_rx_msgid lua_mavlink_register_rx_msgid 1 1
|
|
singleton mavlink manual send_chan lua_mavlink_send_chan 3 1
|
|
singleton mavlink manual receive_chan lua_mavlink_receive_chan 0 3
|
|
singleton mavlink manual block_command lua_mavlink_block_command 1 1
|
|
|
|
include AC_Fence/AC_Fence.h depends AP_FENCE_ENABLED
|
|
include AC_Fence/AC_Fence_config.h
|
|
singleton AC_Fence depends AP_FENCE_ENABLED
|
|
singleton AC_Fence rename fence
|
|
singleton AC_Fence method get_breaches uint8_t
|
|
singleton AC_Fence method get_breach_time uint32_t
|
|
|
|
include AP_Filesystem/AP_Filesystem.h depends AP_FILESYSTEM_FILE_READING_ENABLED
|
|
include AP_Filesystem/AP_Filesystem_config.h
|
|
userdata AP_Filesystem::stat_t depends AP_FILESYSTEM_FILE_READING_ENABLED
|
|
userdata AP_Filesystem::stat_t rename stat_t
|
|
userdata AP_Filesystem::stat_t field size uint32_t read
|
|
userdata AP_Filesystem::stat_t field mode int32_t read
|
|
userdata AP_Filesystem::stat_t field mtime uint32_t read
|
|
userdata AP_Filesystem::stat_t field atime uint32_t read
|
|
userdata AP_Filesystem::stat_t field ctime uint32_t read
|
|
userdata AP_Filesystem::stat_t method is_directory boolean
|
|
|
|
singleton AP_Filesystem rename fs
|
|
singleton AP_Filesystem method stat boolean string AP_Filesystem::stat_t'Null
|
|
singleton AP_Filesystem method format boolean
|
|
singleton AP_Filesystem method format depends AP_FILESYSTEM_FORMAT_ENABLED
|
|
singleton AP_Filesystem method get_format_status uint8_t'skip_check
|
|
singleton AP_Filesystem method get_format_status depends AP_FILESYSTEM_FORMAT_ENABLED
|
|
singleton AP_Filesystem method crc32 boolean string uint32_t'Null
|
|
|
|
include AP_RTC/AP_RTC.h depends AP_RTC_ENABLED
|
|
include AP_RTC/AP_RTC_config.h
|
|
singleton AP_RTC depends AP_RTC_ENABLED
|
|
singleton AP_RTC rename rtc
|
|
singleton AP_RTC method clock_s_to_date_fields boolean uint32_t'skip_check uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null
|
|
singleton AP_RTC method date_fields_to_clock_s uint32_t uint16_t'skip_check int8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check
|
|
|
|
include AP_Networking/AP_Networking.h depends AP_NETWORKING_ENABLED
|
|
include AP_Networking/AP_Networking_Config.h
|
|
singleton AP_Networking depends AP_NETWORKING_ENABLED
|
|
singleton AP_Networking rename networking
|
|
singleton AP_Networking method get_ip_active uint32_t
|
|
singleton AP_Networking method get_netmask_active uint32_t
|
|
singleton AP_Networking method get_gateway_active uint32_t
|
|
singleton AP_Networking method address_to_str string uint32_t'skip_check
|
|
|
|
include AP_VisualOdom/AP_VisualOdom.h
|
|
singleton AP_VisualOdom depends HAL_VISUALODOM_ENABLED
|
|
singleton AP_VisualOdom rename visual_odom
|
|
singleton AP_VisualOdom method healthy boolean
|
|
singleton AP_VisualOdom method quality int8_t
|