/
lua_generated_bindings.cpp
1998 lines (1704 loc) · 59.9 KB
/
lua_generated_bindings.cpp
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
// auto generated bindings, don't manually edit
#include "lua_generated_bindings.h"
#include "lua_boxed_numerics.h"
#include <AP_Param/AP_Param.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_SerialLED/AP_SerialLED.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Relay/AP_Relay.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_Math/AP_Math.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Common/Location.h>
#if !defined(AP_TERRAIN_AVAILABLE) || (AP_TERRAIN_AVAILABLE != 1)
#error Scripting requires terrain to be available
#endif // !defined(AP_TERRAIN_AVAILABLE) || (AP_TERRAIN_AVAILABLE != 1)
static int binding_argcheck(lua_State *L, int expected_arg_count) {
const int args = lua_gettop(L);
if (args > expected_arg_count) {
return luaL_argerror(L, args, "too many arguments");
} else if (args < expected_arg_count) {
return luaL_argerror(L, args, "too few arguments");
}
return 0;
}
int new_Vector2f(lua_State *L) {
luaL_checkstack(L, 2, "Out of stack");
void *ud = lua_newuserdata(L, sizeof(Vector2f));
memset(ud, 0, sizeof(Vector2f));
new (ud) Vector2f();
luaL_getmetatable(L, "Vector2f");
lua_setmetatable(L, -2);
return 1;
}
int new_Vector3f(lua_State *L) {
luaL_checkstack(L, 2, "Out of stack");
void *ud = lua_newuserdata(L, sizeof(Vector3f));
memset(ud, 0, sizeof(Vector3f));
new (ud) Vector3f();
luaL_getmetatable(L, "Vector3f");
lua_setmetatable(L, -2);
return 1;
}
int new_Location(lua_State *L) {
luaL_checkstack(L, 2, "Out of stack");
void *ud = lua_newuserdata(L, sizeof(Location));
memset(ud, 0, sizeof(Location));
new (ud) Location();
luaL_getmetatable(L, "Location");
lua_setmetatable(L, -2);
return 1;
}
Vector2f * check_Vector2f(lua_State *L, int arg) {
void *data = luaL_checkudata(L, arg, "Vector2f");
return (Vector2f *)data;
}
Vector3f * check_Vector3f(lua_State *L, int arg) {
void *data = luaL_checkudata(L, arg, "Vector3f");
return (Vector3f *)data;
}
Location * check_Location(lua_State *L, int arg) {
void *data = luaL_checkudata(L, arg, "Location");
return (Location *)data;
}
static int Vector2f_y(lua_State *L) {
Vector2f *ud = check_Vector2f(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushnumber(L, ud->y);
return 1;
case 2: {
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "y out of range");
const float data_2 = raw_data_2;
ud->y = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Vector2f_x(lua_State *L) {
Vector2f *ud = check_Vector2f(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushnumber(L, ud->x);
return 1;
case 2: {
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "x out of range");
const float data_2 = raw_data_2;
ud->x = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Vector3f_z(lua_State *L) {
Vector3f *ud = check_Vector3f(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushnumber(L, ud->z);
return 1;
case 2: {
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "z out of range");
const float data_2 = raw_data_2;
ud->z = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Vector3f_y(lua_State *L) {
Vector3f *ud = check_Vector3f(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushnumber(L, ud->y);
return 1;
case 2: {
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "y out of range");
const float data_2 = raw_data_2;
ud->y = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Vector3f_x(lua_State *L) {
Vector3f *ud = check_Vector3f(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushnumber(L, ud->x);
return 1;
case 2: {
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "x out of range");
const float data_2 = raw_data_2;
ud->x = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Location_loiter_xtrack(lua_State *L) {
Location *ud = check_Location(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushinteger(L, ud->loiter_xtrack);
return 1;
case 2: {
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
ud->loiter_xtrack = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Location_origin_alt(lua_State *L) {
Location *ud = check_Location(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushinteger(L, ud->origin_alt);
return 1;
case 2: {
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
ud->origin_alt = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Location_terrain_alt(lua_State *L) {
Location *ud = check_Location(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushinteger(L, ud->terrain_alt);
return 1;
case 2: {
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
ud->terrain_alt = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Location_relative_alt(lua_State *L) {
Location *ud = check_Location(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushinteger(L, ud->relative_alt);
return 1;
case 2: {
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
ud->relative_alt = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Location_lng(lua_State *L) {
Location *ud = check_Location(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushinteger(L, ud->lng);
return 1;
case 2: {
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-1800000000, INT32_MIN)) && (raw_data_2 <= MIN(1800000000, INT32_MAX))), 2, "lng out of range");
const int32_t data_2 = raw_data_2;
ud->lng = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Location_lat(lua_State *L) {
Location *ud = check_Location(L, 1);
switch(lua_gettop(L)) {
case 1:
lua_pushinteger(L, ud->lat);
return 1;
case 2: {
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-900000000, INT32_MIN)) && (raw_data_2 <= MIN(900000000, INT32_MAX))), 2, "lat out of range");
const int32_t data_2 = raw_data_2;
ud->lat = data_2;
return 0;
}
default:
return luaL_argerror(L, lua_gettop(L), "too many arguments");
}
}
static int Vector2f_is_zero(lua_State *L) {
binding_argcheck(L, 1);
Vector2f * ud = check_Vector2f(L, 1);
const bool data = ud->is_zero();
lua_pushboolean(L, data);
return 1;
}
static int Vector2f_is_inf(lua_State *L) {
binding_argcheck(L, 1);
Vector2f * ud = check_Vector2f(L, 1);
const bool data = ud->is_inf();
lua_pushboolean(L, data);
return 1;
}
static int Vector2f_is_nan(lua_State *L) {
binding_argcheck(L, 1);
Vector2f * ud = check_Vector2f(L, 1);
const bool data = ud->is_nan();
lua_pushboolean(L, data);
return 1;
}
static int Vector2f_normalize(lua_State *L) {
binding_argcheck(L, 1);
Vector2f * ud = check_Vector2f(L, 1);
ud->normalize();
return 0;
}
static int Vector2f_length(lua_State *L) {
binding_argcheck(L, 1);
Vector2f * ud = check_Vector2f(L, 1);
const float data = ud->length();
lua_pushnumber(L, data);
return 1;
}
static int Vector2f___add(lua_State *L) {
binding_argcheck(L, 2);
Vector2f *ud = check_Vector2f(L, 1);
Vector2f *ud2 = check_Vector2f(L, 2);
new_Vector2f(L);
*check_Vector2f(L, -1) = *ud + *ud2;;
return 1;
}
static int Vector2f___sub(lua_State *L) {
binding_argcheck(L, 2);
Vector2f *ud = check_Vector2f(L, 1);
Vector2f *ud2 = check_Vector2f(L, 2);
new_Vector2f(L);
*check_Vector2f(L, -1) = *ud - *ud2;;
return 1;
}
static int Vector3f_is_zero(lua_State *L) {
binding_argcheck(L, 1);
Vector3f * ud = check_Vector3f(L, 1);
const bool data = ud->is_zero();
lua_pushboolean(L, data);
return 1;
}
static int Vector3f_is_inf(lua_State *L) {
binding_argcheck(L, 1);
Vector3f * ud = check_Vector3f(L, 1);
const bool data = ud->is_inf();
lua_pushboolean(L, data);
return 1;
}
static int Vector3f_is_nan(lua_State *L) {
binding_argcheck(L, 1);
Vector3f * ud = check_Vector3f(L, 1);
const bool data = ud->is_nan();
lua_pushboolean(L, data);
return 1;
}
static int Vector3f_normalize(lua_State *L) {
binding_argcheck(L, 1);
Vector3f * ud = check_Vector3f(L, 1);
ud->normalize();
return 0;
}
static int Vector3f_length(lua_State *L) {
binding_argcheck(L, 1);
Vector3f * ud = check_Vector3f(L, 1);
const float data = ud->length();
lua_pushnumber(L, data);
return 1;
}
static int Vector3f___add(lua_State *L) {
binding_argcheck(L, 2);
Vector3f *ud = check_Vector3f(L, 1);
Vector3f *ud2 = check_Vector3f(L, 2);
new_Vector3f(L);
*check_Vector3f(L, -1) = *ud + *ud2;;
return 1;
}
static int Vector3f___sub(lua_State *L) {
binding_argcheck(L, 2);
Vector3f *ud = check_Vector3f(L, 1);
Vector3f *ud2 = check_Vector3f(L, 2);
new_Vector3f(L);
*check_Vector3f(L, -1) = *ud - *ud2;;
return 1;
}
static int Location_get_distance_NE(lua_State *L) {
binding_argcheck(L, 2);
Location * ud = check_Location(L, 1);
Location & data_2 = *check_Location(L, 2);
const Vector2f &data = ud->get_distance_NE(
data_2);
new_Vector2f(L);
*check_Vector2f(L, -1) = data;
return 1;
}
static int Location_get_distance_NED(lua_State *L) {
binding_argcheck(L, 2);
Location * ud = check_Location(L, 1);
Location & data_2 = *check_Location(L, 2);
const Vector3f &data = ud->get_distance_NED(
data_2);
new_Vector3f(L);
*check_Vector3f(L, -1) = data;
return 1;
}
static int Location_get_bearing(lua_State *L) {
binding_argcheck(L, 2);
Location * ud = check_Location(L, 1);
Location & data_2 = *check_Location(L, 2);
const float data = ud->get_bearing(
data_2);
lua_pushnumber(L, data);
return 1;
}
static int Location_get_vector_from_origin_NEU(lua_State *L) {
binding_argcheck(L, 1);
Location * ud = check_Location(L, 1);
Vector3f data_5002 = {};
const bool data = ud->get_vector_from_origin_NEU(
data_5002);
if (data) {
new_Vector3f(L);
*check_Vector3f(L, -1) = data_5002;
} else {
lua_pushnil(L);
}
return 1;
}
static int Location_offset(lua_State *L) {
binding_argcheck(L, 3);
Location * ud = check_Location(L, 1);
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "argument out of range");
const float data_2 = raw_data_2;
const float raw_data_3 = luaL_checknumber(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3;
ud->offset(
data_2,
data_3);
return 0;
}
static int Location_get_distance(lua_State *L) {
binding_argcheck(L, 2);
Location * ud = check_Location(L, 1);
Location & data_2 = *check_Location(L, 2);
const float data = ud->get_distance(
data_2);
lua_pushnumber(L, data);
return 1;
}
const luaL_Reg Vector2f_meta[] = {
{"y", Vector2f_y},
{"x", Vector2f_x},
{"is_zero", Vector2f_is_zero},
{"is_inf", Vector2f_is_inf},
{"is_nan", Vector2f_is_nan},
{"normalize", Vector2f_normalize},
{"length", Vector2f_length},
{"__add", Vector2f___add},
{"__sub", Vector2f___sub},
{NULL, NULL}
};
const luaL_Reg Vector3f_meta[] = {
{"z", Vector3f_z},
{"y", Vector3f_y},
{"x", Vector3f_x},
{"is_zero", Vector3f_is_zero},
{"is_inf", Vector3f_is_inf},
{"is_nan", Vector3f_is_nan},
{"normalize", Vector3f_normalize},
{"length", Vector3f_length},
{"__add", Vector3f___add},
{"__sub", Vector3f___sub},
{NULL, NULL}
};
const luaL_Reg Location_meta[] = {
{"loiter_xtrack", Location_loiter_xtrack},
{"origin_alt", Location_origin_alt},
{"terrain_alt", Location_terrain_alt},
{"relative_alt", Location_relative_alt},
{"lng", Location_lng},
{"lat", Location_lat},
{"get_distance_NE", Location_get_distance_NE},
{"get_distance_NED", Location_get_distance_NED},
{"get_bearing", Location_get_bearing},
{"get_vector_from_origin_NEU", Location_get_vector_from_origin_NEU},
{"offset", Location_offset},
{"get_distance", Location_get_distance},
{NULL, NULL}
};
static int AP_Param_set_and_save_by_name(lua_State *L) {
AP_Param * ud = AP_Param::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "param not supported on this firmware");
}
binding_argcheck(L, 3);
const char * data_2 = luaL_checkstring(L, 2);
const float raw_data_3 = luaL_checknumber(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3;
const bool data = ud->set_and_save_by_name(
data_2,
data_3);
lua_pushboolean(L, data);
return 1;
}
static int AP_Param_set_by_name(lua_State *L) {
AP_Param * ud = AP_Param::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "param not supported on this firmware");
}
binding_argcheck(L, 3);
const char * data_2 = luaL_checkstring(L, 2);
const float raw_data_3 = luaL_checknumber(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3;
const bool data = ud->set_by_name(
data_2,
data_3);
lua_pushboolean(L, data);
return 1;
}
static int AP_Param_get_by_name(lua_State *L) {
AP_Param * ud = AP_Param::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "param not supported on this firmware");
}
binding_argcheck(L, 2);
const char * data_2 = luaL_checkstring(L, 2);
float data_5003 = {};
const bool data = ud->get_by_name(
data_2,
data_5003);
if (data) {
lua_pushnumber(L, data_5003);
} else {
lua_pushnil(L);
}
return 1;
}
static int SRV_Channels_find_channel(lua_State *L) {
SRV_Channels * ud = SRV_Channels::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "SRV_Channels not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= static_cast<int32_t>(SRV_Channel::k_none)) && (raw_data_2 <= static_cast<int32_t>(SRV_Channel::k_nr_aux_servo_functions-1))), 2, "argument out of range");
const SRV_Channel::Aux_servo_function_t data_2 = static_cast<SRV_Channel::Aux_servo_function_t>(raw_data_2);
uint8_t data_5003 = {};
const bool data = ud->find_channel(
data_2,
data_5003);
if (data) {
lua_pushinteger(L, data_5003);
} else {
lua_pushnil(L);
}
return 1;
}
static int AP_SerialLED_send(lua_State *L) {
AP_SerialLED * ud = AP_SerialLED::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "serialLED not supported on this firmware");
}
binding_argcheck(L, 1);
ud->send();
return 0;
}
static int AP_SerialLED_set_RGB(lua_State *L) {
AP_SerialLED * ud = AP_SerialLED::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "serialLED not supported on this firmware");
}
binding_argcheck(L, 6);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t raw_data_3 = *check_uint32_t(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0U, 0U)) && (raw_data_3 <= MIN(UINT32_MAX, UINT32_MAX))), 3, "argument out of range");
const uint32_t data_3 = static_cast<uint32_t>(raw_data_3);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 4);
luaL_argcheck(L, ((raw_data_4 >= MAX(0, 0)) && (raw_data_4 <= MIN(UINT8_MAX, UINT8_MAX))), 4, "argument out of range");
const uint8_t data_4 = static_cast<uint8_t>(raw_data_4);
const lua_Integer raw_data_5 = luaL_checkinteger(L, 5);
luaL_argcheck(L, ((raw_data_5 >= MAX(0, 0)) && (raw_data_5 <= MIN(UINT8_MAX, UINT8_MAX))), 5, "argument out of range");
const uint8_t data_5 = static_cast<uint8_t>(raw_data_5);
const lua_Integer raw_data_6 = luaL_checkinteger(L, 6);
luaL_argcheck(L, ((raw_data_6 >= MAX(0, 0)) && (raw_data_6 <= MIN(UINT8_MAX, UINT8_MAX))), 6, "argument out of range");
const uint8_t data_6 = static_cast<uint8_t>(raw_data_6);
ud->set_RGB(
data_2,
data_3,
data_4,
data_5,
data_6);
return 0;
}
static int AP_SerialLED_set_num_LEDs(lua_State *L) {
AP_SerialLED * ud = AP_SerialLED::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "serialLED not supported on this firmware");
}
binding_argcheck(L, 3);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(32, UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->set_num_LEDs(
data_2,
data_3);
lua_pushboolean(L, data);
return 1;
}
static int AP_Vehicle_set_mode(lua_State *L) {
AP_Vehicle * ud = AP_Vehicle::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "vehicle not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(UINT8_MAX, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const bool data = ud->set_mode(
data_2,
ModeReason::SCRIPTING);
lua_pushboolean(L, data);
return 1;
}
static int GCS_set_message_interval(lua_State *L) {
GCS * ud = GCS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gcs not supported on this firmware");
}
binding_argcheck(L, 4);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(MAVLINK_COMM_NUM_BUFFERS, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t raw_data_3 = *check_uint32_t(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0U, 0U)) && (raw_data_3 <= MIN(UINT32_MAX, UINT32_MAX))), 3, "argument out of range");
const uint32_t data_3 = static_cast<uint32_t>(raw_data_3);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 4);
luaL_argcheck(L, ((raw_data_4 >= MAX(-1, INT32_MIN)) && (raw_data_4 <= MIN(INT32_MAX, INT32_MAX))), 4, "argument out of range");
const int32_t data_4 = raw_data_4;
const MAV_RESULT &data = ud->set_message_interval(
data_2,
data_3,
data_4);
lua_pushinteger(L, data);
return 1;
}
static int GCS_send_text(lua_State *L) {
GCS * ud = GCS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gcs not supported on this firmware");
}
binding_argcheck(L, 3);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= static_cast<int32_t>(MAV_SEVERITY_EMERGENCY)) && (raw_data_2 <= static_cast<int32_t>(MAV_SEVERITY_DEBUG))), 2, "argument out of range");
const MAV_SEVERITY data_2 = static_cast<MAV_SEVERITY>(raw_data_2);
const char * data_3 = luaL_checkstring(L, 3);
ud->send_text(
data_2,
"%s",
data_3);
return 0;
}
static int AP_Relay_toggle(lua_State *L) {
AP_Relay * ud = AP_Relay::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "relay not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
ud->toggle(
data_2);
return 0;
}
static int AP_Relay_enabled(lua_State *L) {
AP_Relay * ud = AP_Relay::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "relay not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const bool data = ud->enabled(
data_2);
lua_pushboolean(L, data);
return 1;
}
static int AP_Relay_off(lua_State *L) {
AP_Relay * ud = AP_Relay::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "relay not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
ud->off(
data_2);
return 0;
}
static int AP_Relay_on(lua_State *L) {
AP_Relay * ud = AP_Relay::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "relay not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
ud->on(
data_2);
return 0;
}
static int AP_Terrain_height_above_terrain(lua_State *L) {
AP_Terrain * ud = AP_Terrain::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "terrain not supported on this firmware");
}
binding_argcheck(L, 2);
float data_5002 = {};
const bool data_3 = static_cast<bool>(lua_toboolean(L, 3));
const bool data = ud->height_above_terrain(
data_5002,
data_3);
if (data) {
lua_pushnumber(L, data_5002);
} else {
lua_pushnil(L);
}
return 1;
}
static int AP_Terrain_height_terrain_difference_home(lua_State *L) {
AP_Terrain * ud = AP_Terrain::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "terrain not supported on this firmware");
}
binding_argcheck(L, 2);
float data_5002 = {};
const bool data_3 = static_cast<bool>(lua_toboolean(L, 3));
const bool data = ud->height_terrain_difference_home(
data_5002,
data_3);
if (data) {
lua_pushnumber(L, data_5002);
} else {
lua_pushnil(L);
}
return 1;
}
static int AP_Terrain_height_amsl(lua_State *L) {
AP_Terrain * ud = AP_Terrain::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "terrain not supported on this firmware");
}
binding_argcheck(L, 3);
Location & data_2 = *check_Location(L, 2);
float data_5003 = {};
const bool data_4 = static_cast<bool>(lua_toboolean(L, 4));
const bool data = ud->height_amsl(
data_2,
data_5003,
data_4);
if (data) {
lua_pushnumber(L, data_5003);
} else {
lua_pushnil(L);
}
return 1;
}
static int AP_Terrain_status(lua_State *L) {
AP_Terrain * ud = AP_Terrain::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "terrain not supported on this firmware");
}
binding_argcheck(L, 1);
const uint8_t data = ud->status();
lua_pushinteger(L, data);
return 1;
}
static int AP_Terrain_enabled(lua_State *L) {
AP_Terrain * ud = AP_Terrain::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "terrain not supported on this firmware");
}
binding_argcheck(L, 1);
const bool data = ud->enabled();
lua_pushboolean(L, data);
return 1;
}
static int RangeFinder_num_sensors(lua_State *L) {
RangeFinder * ud = RangeFinder::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "rangefinder not supported on this firmware");
}
binding_argcheck(L, 1);
const uint8_t data = ud->num_sensors();
lua_pushinteger(L, data);
return 1;
}
static int AP_Notify_play_tune(lua_State *L) {
AP_Notify * ud = AP_Notify::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "notify not supported on this firmware");
}
binding_argcheck(L, 2);
const char * data_2 = luaL_checkstring(L, 2);
ud->play_tune(
data_2);
return 0;
}
static int AP_GPS_first_unconfigured_gps(lua_State *L) {
AP_GPS * ud = AP_GPS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gps not supported on this firmware");
}
binding_argcheck(L, 1);
uint8_t data_5002 = {};
const bool data = ud->first_unconfigured_gps(
data_5002);
if (data) {
lua_pushinteger(L, data_5002);
} else {
lua_pushnil(L);
}
return 1;
}
static int AP_GPS_get_antenna_offset(lua_State *L) {
AP_GPS * ud = AP_GPS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gps not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const Vector3f &data = ud->get_antenna_offset(
data_2);
new_Vector3f(L);
*check_Vector3f(L, -1) = data;
return 1;
}
static int AP_GPS_have_vertical_velocity(lua_State *L) {
AP_GPS * ud = AP_GPS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gps not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const bool data = ud->have_vertical_velocity(
data_2);
lua_pushboolean(L, data);
return 1;
}
static int AP_GPS_last_message_time_ms(lua_State *L) {
AP_GPS * ud = AP_GPS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gps not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t data = ud->last_message_time_ms(
data_2);
new_uint32_t(L);
*static_cast<uint32_t *>(luaL_checkudata(L, -1, "uint32_t")) = data;
return 1;
}
static int AP_GPS_last_fix_time_ms(lua_State *L) {
AP_GPS * ud = AP_GPS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gps not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t data = ud->last_fix_time_ms(
data_2);
new_uint32_t(L);
*static_cast<uint32_t *>(luaL_checkudata(L, -1, "uint32_t")) = data;
return 1;
}
static int AP_GPS_get_vdop(lua_State *L) {
AP_GPS * ud = AP_GPS::get_singleton();