-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdocs.lua
2682 lines (2095 loc) · 60.1 KB
/
docs.lua
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
-- ArduPilot lua scripting documentation in EmmyLua Annotations
-- This file should be auto generated and then manual edited
-- generate with --scripting-docs, eg ./waf copter --scripting-docs
-- see: https://github.com/sumneko/lua-language-server/wiki/EmmyLua-Annotations
-- luacheck: ignore 121 (Setting a read-only global variable)
-- luacheck: ignore 122 (Setting a read-only field of a global variable)
-- luacheck: ignore 212 (Unused argument)
-- luacheck: ignore 241 (Local variable is mutated but never accessed)
-- set and get for field types share function names
---@diagnostic disable: duplicate-set-field
-- manual bindings
---@class uint32_t_ud
local uint32_t_ud = {}
-- create uint32_t_ud with optional value
---@param value? number|integer
---@return uint32_t_ud
function uint32_t(value) end
-- Convert to number
---@return number
function uint32_t_ud:tofloat() end
-- Convert to integer
---@return integer
function uint32_t_ud:toint() end
-- system time in milliseconds
---@return uint32_t_ud -- milliseconds
function millis() end
-- system time in microseconds
---@return uint32_t_ud -- microseconds
function micros() end
-- receive mission command from running mission
---@return uint32_t_ud|nil -- command start time milliseconds
---@return integer|nil -- command param 1
---@return number|nil -- command param 2
---@return number|nil -- command param 3
---@return number|nil -- command param 4
function mission_receive() end
-- data flash logging to SD card
---@class logger
logger = {}
-- write value to data flash log with given types and names, optional units and multipliers, timestamp will be automatically added
---@param name string -- up to 4 characters
---@param labels string -- comma separated value labels, up to 58 characters
---@param format string -- type format string, see https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Logger/README.md
---@param units? string -- optional units string
---@param multipliers? string -- optional multipliers string
---@param data1 integer|number|uint32_t_ud|string -- data to be logged, type to match format string
function logger:write(name, labels, format, units, multipliers, data1, ...) end
-- i2c bus interaction
---@class i2c
i2c = {}
-- get a i2c device handler
---@param bus integer -- bus number
---@param address integer -- device address 0 to 128
---@param clock? uint32_t_ud -- optional bus clock, default 400000
---@param smbus? boolean -- optional sumbus flag, default false
---@return AP_HAL__I2CDevice_ud
function i2c:get_device(bus, address, clock, smbus) end
-- EFI state structure
---@class EFI_State_ud
local EFI_State_ud = {}
---@return EFI_State_ud
function EFI_State() end
-- set field
---@param value number
function EFI_State_ud:pt_compensation(value) end
-- set field
---@param value number
function EFI_State_ud:throttle_out(value) end
-- set field
---@param value number
function EFI_State_ud:ignition_voltage(value) end
-- set field
---@param value Cylinder_Status_ud
function EFI_State_ud:cylinder_status(value) end
-- set field
---@param value integer
function EFI_State_ud:ecu_index(value) end
-- set field
---@param value integer
function EFI_State_ud:throttle_position_percent(value) end
-- set field
---@param value number
function EFI_State_ud:estimated_consumed_fuel_volume_cm3(value) end
-- set field
---@param value number
function EFI_State_ud:fuel_consumption_rate_cm3pm(value) end
-- set field
---@param value number
function EFI_State_ud:fuel_pressure(value) end
-- set field
---@param status integer
---| '0' # Not supported
---| '1' # Ok
---| '2' # Below nominal
---| '3' # Above nominal
function EFI_State_ud:fuel_pressure_status(status) end
-- set field
---@param value number
function EFI_State_ud:oil_temperature(value) end
-- set field
---@param value number
function EFI_State_ud:oil_pressure(value) end
-- set field
---@param value number
function EFI_State_ud:coolant_temperature(value) end
-- set field
---@param value number
function EFI_State_ud:intake_manifold_temperature(value) end
-- set field
---@param value number
function EFI_State_ud:intake_manifold_pressure_kpa(value) end
-- set field
---@param value number
function EFI_State_ud:atmospheric_pressure_kpa(value) end
-- set field
---@param value number
function EFI_State_ud:spark_dwell_time_ms(value) end
-- set field
---@param value uint32_t_ud
function EFI_State_ud:engine_speed_rpm(value) end
-- set field
---@param value integer
function EFI_State_ud:engine_load_percent(value) end
-- set field
---@param value boolean
function EFI_State_ud:general_error(value) end
-- set field
---@param value uint32_t_ud
function EFI_State_ud:last_updated_ms(value) end
-- EFI Cylinder_Status structure
---@class Cylinder_Status_ud
local Cylinder_Status_ud = {}
---@return Cylinder_Status_ud
function Cylinder_Status() end
-- set field
---@param value number
function Cylinder_Status_ud:lambda_coefficient(value) end
-- set field
---@param value number
function Cylinder_Status_ud:exhaust_gas_temperature(value) end
-- set field
---@param value number
function Cylinder_Status_ud:cylinder_head_temperature(value) end
-- set field
---@param value number
function Cylinder_Status_ud:injection_time_ms(value) end
-- set field
---@param value number
function Cylinder_Status_ud:ignition_timing_deg(value) end
-- desc
---@class efi
efi = {}
-- desc
---@param instance integer
---@return AP_EFI_Backend_ud
function efi:get_backend(instance) end
-- CAN bus interaction
---@class CAN
CAN = {}
-- get a CAN bus device handler first scripting driver
---@param buffer_len uint32_t_ud -- buffer length 1 to 25
---@return ScriptingCANBuffer_ud
function CAN:get_device(buffer_len) end
-- get a CAN bus device handler second scripting driver
---@param buffer_len uint32_t_ud -- buffer length 1 to 25
---@return ScriptingCANBuffer_ud
function CAN:get_device2(buffer_len) end
-- Auto generated binding
-- desc
---@class CANFrame_ud
local CANFrame_ud = {}
---@return CANFrame_ud
function CANFrame() end
-- get field
---@return integer
function CANFrame_ud:dlc() end
-- set field
---@param value integer
function CANFrame_ud:dlc(value) end
-- get array field
---@param index integer
---@return integer
function CANFrame_ud:data(index) end
-- set array field
---@param index integer
---@param value integer
function CANFrame_ud:data(index, value) end
-- get field
---@return uint32_t_ud
function CANFrame_ud:id() end
-- set field
---@param value uint32_t_ud
function CANFrame_ud:id(value) end
-- desc
---@return boolean
function CANFrame_ud:isErrorFrame() end
-- desc
---@return boolean
function CANFrame_ud:isRemoteTransmissionRequest() end
-- desc
---@return boolean
function CANFrame_ud:isExtended() end
-- desc
---@return integer
function CANFrame_ud:id_signed() end
-- desc
---@class motor_factor_table_ud
local motor_factor_table_ud = {}
---@return motor_factor_table_ud
function motor_factor_table() end
-- get array field
---@param index integer
---@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 AP_HAL__PWMSource_ud
local AP_HAL__PWMSource_ud = {}
---@return AP_HAL__PWMSource_ud
function PWMSource() end
-- desc
---@return integer
function AP_HAL__PWMSource_ud:get_pwm_avg_us() end
-- desc
---@return integer
function AP_HAL__PWMSource_ud:get_pwm_us() end
-- desc
---@param pin_number integer
---@return boolean
function AP_HAL__PWMSource_ud:set_pin(pin_number) end
-- desc
---@class mavlink_mission_item_int_t_ud
local mavlink_mission_item_int_t_ud = {}
---@return mavlink_mission_item_int_t_ud
function mavlink_mission_item_int_t() end
-- get field
---@return integer
function mavlink_mission_item_int_t_ud:current() end
-- set field
---@param value integer
function mavlink_mission_item_int_t_ud:current(value) end
-- get field
---@return integer
function mavlink_mission_item_int_t_ud:frame() end
-- set field
---@param value integer
function mavlink_mission_item_int_t_ud:frame(value) end
-- get field
---@return integer
function mavlink_mission_item_int_t_ud:command() end
-- set field
---@param value integer
function mavlink_mission_item_int_t_ud:command(value) end
-- get field
---@return integer
function mavlink_mission_item_int_t_ud:seq() end
-- set field
---@param value integer
function mavlink_mission_item_int_t_ud:seq(value) end
-- get field
---@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
-- set field
---@param value integer
function mavlink_mission_item_int_t_ud:y(value) end
-- get field
---@return integer
function mavlink_mission_item_int_t_ud:x() end
-- set field
---@param value integer
function mavlink_mission_item_int_t_ud:x(value) end
-- get field
---@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
local Parameter_ud = {}
---@return Parameter_ud
---@param name? string
function Parameter(name) end
-- desc
---@param value number
---@return boolean
function Parameter_ud:set_default(value) end
-- desc
---@return boolean
function Parameter_ud:configured() end
-- desc
---@param value number
---@return boolean
function Parameter_ud:set_and_save(value) end
-- desc
---@param value number
---@return boolean
function Parameter_ud:set(value) end
-- desc
---@return number|nil
function Parameter_ud:get() end
-- desc
---@param key integer
---@param group_element uint32_t_ud
---@param type integer
---| '1' # AP_PARAM_INT8
---| '2' # AP_PARAM_INT16
---| '3' # AP_PARAM_INT32
---| '4' # AP_PARAM_FLOAT
---@return boolean
function Parameter_ud:init_by_info(key, group_element, type) end
-- desc
---@param name string
---@return boolean
function Parameter_ud:init(name) end
-- desc
---@class Vector2f_ud
local Vector2f_ud = {}
---@return Vector2f_ud
function Vector2f() end
-- copy
---@return Vector2f_ud
function Vector2f_ud:copy() end
-- get field
---@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 angle_rad number
function Vector2f_ud:rotate(angle_rad) end
-- desc
---@return boolean
function Vector2f_ud:is_zero() end
-- desc
---@return boolean
function Vector2f_ud:is_inf() end
-- desc
---@return boolean
function Vector2f_ud:is_nan() end
-- desc
function Vector2f_ud:normalize() end
-- desc
---@return number
function Vector2f_ud:length() end
-- desc
---@return number
function Vector2f_ud:angle() end
-- desc
---@class Vector3f_ud
local Vector3f_ud = {}
---@return Vector3f_ud
function Vector3f() end
-- copy
---@return Vector3f_ud
function Vector3f_ud:copy() end
-- get field
---@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 scale_factor number
---@return Vector3f_ud
function Vector3f_ud:scale(scale_factor) end
-- desc
---@param vector Vector3f_ud
---@return Vector3f_ud
function Vector3f_ud:cross(vector) end
-- desc
---@param vector Vector3f_ud
---@return number
function Vector3f_ud:dot(vector) end
-- desc
---@return boolean
function Vector3f_ud:is_zero() end
-- desc
---@return boolean
function Vector3f_ud:is_inf() end
-- desc
---@return boolean
function Vector3f_ud:is_nan() end
-- desc
function Vector3f_ud:normalize() end
-- desc
---@return number
function Vector3f_ud:length() end
-- Computes angle between this vector and vector v2
---@param v2 Vector3f_ud
---@return number
function Vector3f_ud:angle(v2) end
-- desc
---@param param1 number -- XY rotation in radians
function Vector3f_ud:rotate_xy(param1) end
-- desc
---@return Vector2f_ud
function Vector3f_ud:xy() end
-- desc
---@class Quaternion_ud
local Quaternion_ud = {}
---@return Quaternion_ud
function Quaternion() end
-- get field
---@return number
function Quaternion_ud:q4() end
-- set field
---@param value number
function Quaternion_ud:q4(value) end
-- get field
---@return number
function Quaternion_ud:q3() end
-- set field
---@param value number
function Quaternion_ud:q3(value) end
-- get field
---@return number
function Quaternion_ud:q2() end
-- set field
---@param value number
function Quaternion_ud:q2(value) end
-- get field
---@return number
function Quaternion_ud:q1() end
-- set field
---@param value number
function Quaternion_ud:q1(value) end
-- Applies rotation to vector argument
---@param vec Vector3f_ud
function Quaternion_ud:earth_to_body(vec) end
-- Returns inverse of quaternion
---@return Quaternion_ud
function Quaternion_ud:inverse() end
-- Integrates angular velocity over small time delta
---@param angular_velocity Vector3f_ud
---@param time_delta number
function Quaternion_ud:from_angular_velocity(angular_velocity, time_delta) end
-- Constructs Quaternion from axis and angle
---@param axis Vector3f_ud
---@param angle number
function Quaternion_ud:from_axis_angle(axis, angle) end
-- Converts Quaternion to axis-angle representation
---@param axis_angle Vector3f_ud
function Quaternion_ud:to_axis_angle(axis_angle) end
-- Construct quaternion from Euler angles
---@param roll number
---@param pitch number
---@param yaw number
function Quaternion_ud:from_euler(roll, pitch, yaw) end
-- Returns yaw component of quaternion
---@return number
function Quaternion_ud:get_euler_yaw() end
-- Returns pitch component of quaternion
---@return number
function Quaternion_ud:get_euler_pitch() end
-- Returns roll component of quaternion
---@return number
function Quaternion_ud:get_euler_roll() end
-- Mutates quaternion have length 1
function Quaternion_ud:normalize() end
-- Returns length or norm of quaternion
---@return number
function Quaternion_ud:length() end
-- desc
---@class Location_ud
local Location_ud = {}
---@return Location_ud
function Location() end
-- copy
---@return Location_ud
function Location_ud:copy() end
-- get field
---@return boolean
function Location_ud:loiter_xtrack() end
-- set field
---@param value boolean
function Location_ud:loiter_xtrack(value) end
-- get field
---@return boolean
function Location_ud:origin_alt() end
-- set field
---@param value boolean
function Location_ud:origin_alt(value) end
-- get field
---@return boolean
function Location_ud:terrain_alt() end
-- set field
---@param value boolean
function Location_ud:terrain_alt(value) end
-- get field
---@return boolean
function Location_ud:relative_alt() end
-- set field
---@param value boolean
function Location_ud:relative_alt(value) end
-- get field
---@return integer
function Location_ud:alt() end
-- set field
---@param value integer
function Location_ud:alt(value) end
-- get field
---@return integer
function Location_ud:lng() end
-- set field
---@param value integer
function Location_ud:lng(value) end
-- get field
---@return integer
function Location_ud:lat() end
-- set field
---@param value integer
function Location_ud:lat(value) end
-- get altitude frame
---@return integer
---| '0' # ABSOLUTE
---| '1' # ABOVE_HOME
---| '2' # ABOVE_ORIGIN
---| '3' # ABOVE_TERRAIN
function Location_ud:get_alt_frame() end
-- desc
---@param desired_frame integer
---| '0' # ABSOLUTE
---| '1' # ABOVE_HOME
---| '2' # ABOVE_ORIGIN
---| '3' # ABOVE_TERRAIN
---@return boolean
function Location_ud:change_alt_frame(desired_frame) end
-- desc
---@param loc Location_ud
---@return Vector2f_ud
function Location_ud:get_distance_NE(loc) end
-- desc
---@param loc Location_ud
---@return Vector3f_ud
function Location_ud:get_distance_NED(loc) end
-- desc
---@param loc Location_ud
---@return number
function Location_ud:get_bearing(loc) end
-- desc
---@return Vector3f_ud|nil
function Location_ud:get_vector_from_origin_NEU() end
-- desc
---@param bearing_deg number
---@param distance number
function Location_ud:offset_bearing(bearing_deg, distance) end
-- desc
---@param bearing_deg number
---@param pitch_deg number
---@param distance number
function Location_ud:offset_bearing_and_pitch(bearing_deg, pitch_deg, distance) end
-- desc
---@param ofs_north number
---@param ofs_east number
function Location_ud:offset(ofs_north, ofs_east) end
-- desc
---@param loc Location_ud
---@return number
function Location_ud:get_distance(loc) end
-- desc
---@class AP_EFI_Backend_ud
local AP_EFI_Backend_ud = {}
-- desc
---@param state EFI_State_ud
---@return boolean
function AP_EFI_Backend_ud:handle_scripting(state) end
-- desc
---@class ScriptingCANBuffer_ud
local ScriptingCANBuffer_ud = {}
-- desc
---@return CANFrame_ud|nil
function ScriptingCANBuffer_ud:read_frame() end
-- desc
---@param frame CANFrame_ud
---@param timeout_us uint32_t_ud
---@return boolean
function ScriptingCANBuffer_ud:write_frame(frame, timeout_us) end
-- desc
---@class AP_HAL__AnalogSource_ud
local AP_HAL__AnalogSource_ud = {}
-- desc
---@return number
function AP_HAL__AnalogSource_ud:voltage_average_ratiometric() end
-- desc
---@return number
function AP_HAL__AnalogSource_ud:voltage_latest() end
-- desc
---@return number
function AP_HAL__AnalogSource_ud:voltage_average() end
-- desc
---@param pin_number integer
---@return boolean
function AP_HAL__AnalogSource_ud:set_pin(pin_number) end
-- desc
---@class AP_HAL__I2CDevice_ud
local AP_HAL__I2CDevice_ud = {}
-- desc
---@param address integer
function AP_HAL__I2CDevice_ud:set_address(address) end
-- If no read length is provided a single register will be read and returned.
-- If read length is provided a table of register values are returned.
---@param register_num integer
---@param read_length? integer
---@return integer|table|nil
function AP_HAL__I2CDevice_ud:read_registers(register_num, read_length) end
-- desc
---@param register_num integer
---@param value integer
---@return boolean
function AP_HAL__I2CDevice_ud:write_register(register_num, value) end
-- desc
---@param retries integer
function AP_HAL__I2CDevice_ud:set_retries(retries) end
-- desc
---@class AP_HAL__UARTDriver_ud
local AP_HAL__UARTDriver_ud = {}
-- desc
---@param flow_control_setting integer
---| '0' # disabled
---| '1' # enabled
---| '2' # auto
function AP_HAL__UARTDriver_ud:set_flow_control(flow_control_setting) end
-- desc
---@return uint32_t_ud
function AP_HAL__UARTDriver_ud:available() end
-- desc
---@param value integer
---@return uint32_t_ud
function AP_HAL__UARTDriver_ud:write(value) end
-- desc
---@return integer
function AP_HAL__UARTDriver_ud:read() end
-- desc
---@param baud_rate uint32_t_ud
function AP_HAL__UARTDriver_ud:begin(baud_rate) end
-- desc
---@class RC_Channel_ud
local RC_Channel_ud = {}
-- desc
---@return number
function RC_Channel_ud:norm_input_ignore_trim() end
-- desc
---@param PWM integer
function RC_Channel_ud:set_override(PWM) end
-- desc
---@return integer
function RC_Channel_ud:get_aux_switch_pos() end
-- desc return input on a channel from -1 to 1, centered on the trim. Ignores the deadzone
---@return number
function RC_Channel_ud:norm_input() end
-- desc return input on a channel from -1 to 1, centered on the trim. Returns zero when within deadzone of the trim
---@return number
function RC_Channel_ud:norm_input_dz() end
-- desc
---@class winch
winch = {}
-- desc
---@return number
function winch:get_rate_max() end
-- desc
---@param param1 number
function winch:set_desired_rate(param1) end
-- desc
---@param param1 number
function winch:release_length(param1) end
-- desc
function winch:relax() end
-- desc
---@return boolean
function winch:healthy() end
-- desc
---@class mount
mount = {}
-- desc
---@param param1 integer
---@return integer|nil -- pic_count
---@return boolean|nil -- record_video
---@return integer|nil -- zoom_step
---@return integer|nil -- focus_step
---@return boolean|nil -- auto_focus
function mount:get_camera_state(param1) end
-- desc
---@param instance integer
---@param roll_deg number
---@param pitch_deg number
---@param yaw_deg number
function mount:set_attitude_euler(instance, roll_deg, pitch_deg, yaw_deg) end
-- desc
---@param instance integer
---@return Location_ud|nil