-
Notifications
You must be signed in to change notification settings - Fork 19
/
Copy pathardrone3.xml
3583 lines (3575 loc) · 116 KB
/
ardrone3.xml
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
<?xml version="1.0" encoding="UTF-8"?>
<!--
Copyright (C) 2014 Parrot SA
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in
the documentation and/or other materials provided with the
distribution.
* Neither the name of Parrot nor the names
of its contributors may be used to endorse or promote products
derived from this software without specific prior written
permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
-->
<project name="ardrone3" id="1">
All ARDrone3-only commands
<class name="Piloting" id="0">
All commands related to piloting the drone
<cmd name="TakeOff" id="1">
<comment
title="Take off"
desc="Ask the drone to take off.\n
On the fixed wings (such as Disco): not used except to cancel a land."
support="0901;090c;090e;0914;0919"
result="On the quadcopters: the drone takes off if its [FlyingState](#1-4-1) was landed.\n
On the fixed wings, the landing process is aborted if the [FlyingState](#1-4-1) was landing.\n
Then, event [FlyingState](#1-4-1) is triggered."/>
<expectations>
<immediate>
#1-4-1(state: takingoff)
</immediate>
</expectations>
</cmd>
<cmd name="PCMD" id="2" buffer="NON_ACK">
<comment
title="Move the drone"
desc="Move the drone.\n
The libARController is sending the command each 50ms.\n\n
**Please note that you should call setPilotingPCMD and not sendPilotingPCMD because the libARController is handling the periodicity and the buffer on which it is sent.**"
support="0901;090c;090e;0914;0919"
result="The drone moves! Yaaaaay!\n
Event [SpeedChanged](#1-4-5), [AttitudeChanged](#1-4-6) and [GpsLocationChanged](#1-4-9) (only if gps of the drone has fixed) are triggered."/>
<arg name="flag" type="u8">
Boolean flag: 1 if the roll and pitch values should be taken in consideration. 0 otherwise
</arg>
<arg name="roll" type="i8">
Roll angle as signed percentage.
On copters:
Roll angle expressed as signed percentage of the max pitch/roll setting, in range [-100, 100]
-100 corresponds to a roll angle of max pitch/roll to the left (drone will fly left)
100 corresponds to a roll angle of max pitch/roll to the right (drone will fly right)
This value may be clamped if necessary, in order to respect the maximum supported physical tilt of the copter.
On fixed wings:
Roll angle expressed as signed percentage of the physical max roll of the wing, in range [-100, 100]
Negative value makes the plane fly to the left
Positive value makes the plane fly to the right
</arg>
<arg name="pitch" type="i8">
Pitch angle as signed percentage.
On copters:
Expressed as signed percentage of the max pitch/roll setting, in range [-100, 100]
-100 corresponds to a pitch angle of max pitch/roll towards sky (drone will fly backward)
100 corresponds to a pitch angle of max pitch/roll towards ground (drone will fly forward)
This value may be clamped if necessary, in order to respect the maximum supported physical tilt of the copter.
On fixed wings:
Expressed as signed percentage of the physical max pitch of the wing, in range [-100, 100]
Negative value makes the plane fly in direction of the sky
Positive value makes the plane fly in direction of the ground
</arg>
<arg name="yaw" type="i8">
Yaw rotation speed as signed percentage.
On copters:
Expressed as signed percentage of the max yaw rotation speed setting, in range [-100, 100].
-100 corresponds to a counter-clockwise rotation of max yaw rotation speed
100 corresponds to a clockwise rotation of max yaw rotation speed
This value may be clamped if necessary, in order to respect the maximum supported physical tilt of the copter.
On fixed wings:
Giving more than a fixed value (75% for the moment) triggers a circle.
Positive value will trigger a clockwise circling
Negative value will trigger a counter-clockwise circling
</arg>
<arg name="gaz" type="i8">
Throttle as signed percentage.
On copters:
Expressed as signed percentage of the max vertical speed setting, in range [-100, 100]
-100 corresponds to a max vertical speed towards ground
100 corresponds to a max vertical speed towards sky
This value may be clamped if necessary, in order to respect the maximum supported physical tilt of the copter.
During the landing phase, putting some positive gaz will cancel the land.
On fixed wings:
Expressed as signed percentage of the physical max throttle, in range [-100, 100]
Negative value makes the plane fly slower
Positive value makes the plane fly faster
</arg>
<arg name="timestampAndSeqNum" type="u32">
Command timestamp in milliseconds (low 24 bits) + command sequence number (high 8 bits) [0;255].
</arg>
</cmd>
<cmd name="Landing" id="3">
<comment
title="Land"
desc="Land.\n
Please note that on copters, if you put some positive gaz (in the [PilotingCommand](#1-0-2)) during the landing, it will cancel it."
support="0901;090c;090e;0914;0919"
result="On the copters, the drone lands if its [FlyingState](#1-4-1) was taking off, hovering or flying.\n
On the fixed wings, the drone lands if its [FlyingState](#1-4-1) was hovering or flying.\n
Then, event [FlyingState](#1-4-1) is triggered."/>
<expectations>
<immediate>
#1-4-1(state: landing)
</immediate>
</expectations>
</cmd>
<cmd name="Emergency" id="4" buffer="HIGH_PRIO" timeout="RETRY">
<comment
title="Cut out the motors"
desc="Cut out the motors.\n
This cuts immediatly the motors. The drone will fall.\n
This command is sent on a dedicated high priority buffer which will infinitely retry to send it if the command is not delivered."
support="0901;090c;090e;0914;0919"
result="The drone immediatly cuts off its motors.\n
Then, event [FlyingState](#1-4-1) is triggered."/>
<expectations>
<immediate>
#1-4-1(state: emergency)
</immediate>
</expectations>
</cmd>
<cmd name="NavigateHome" id="5">
<comment
title="Return home"
desc="Return home.\n
Ask the drone to fly to its [HomePosition](#1-24-0).\n
The availability of the return home can be get from [ReturnHomeState](#1-4-3).\n
Please note that the drone will wait to be hovering to start its return home. This means that it will wait to have a [flag](#1-0-2) set at 0."
support="0901;090c;090e;0914;0919"
result="The drone will fly back to its home position.\n
Then, event [ReturnHomeState](#1-4-3) is triggered.\n
You can get a state pending if the drone is not ready to start its return home process but will do it as soon as it is possible."/>
<expectations>
<immediate>
#1-4-3(state: inProgress, reason: userRequest)
|#1-4-3(state: pending, reason: userRequest)
|#1-4-3(state: available, reason: stopped)
</immediate>
</expectations>
<arg name="start" type="u8">
1 to start the navigate home, 0 to stop it
</arg>
</cmd>
<cmd name="moveBy" id="7">
<comment
title="Move the drone to a relative position"
desc="Move the drone to a relative position and rotate heading by a given angle.\n
Moves are relative to the current drone orientation, (drone's reference).\n
Also note that the given rotation will not modify the move (i.e. moves are always rectilinear)."
support="0901:3.3.0;090c:3.3.0;0914;0919"
result="The drone will move of the given offsets.\n
Then, event [RelativeMoveEnded](#1-34-0) is triggered.\n
If you send a second relative move command, the drone will trigger a [RelativeMoveEnded](#1-34-0) with the offsets it managed to do before this new command and the value of error set to interrupted."/>
<expectations>
<immediate>
#1-34-0
</immediate>
</expectations>
<arg name="dX" type="float">
Wanted displacement along the front axis [m]
</arg>
<arg name="dY" type="float">
Wanted displacement along the right axis [m]
</arg>
<arg name="dZ" type="float">
Wanted displacement along the down axis [m]
</arg>
<arg name="dPsi" type="float">
Wanted rotation of heading [rad]
</arg>
</cmd>
<cmd name="UserTakeOff" id="8">
<comment
title="Prepare the drone to take off"
desc="Prepare the drone to take off.\n
On copters: initiates the thrown takeoff. Note that the drone will do the thrown take off
even if it is steady.\n
On fixed wings: initiates the take off process on the fixed wings.\n\n
Setting the state to 0 will cancel the preparation. You can cancel it before that the drone takes off."
support="090e;090c:4.3.0;0914;0919"
result="The drone will arm its motors if not already armed.\n
Then, event [FlyingState](#1-4-1) is triggered with state set at motor ramping.\n
Then, event [FlyingState](#1-4-1) is triggered with state set at userTakeOff.\n
Then user can throw the drone to make it take off."/>
<expectations>
<immediate>
#1-4-1
</immediate>
</expectations>
<arg name="state" type="u8">
State of user take off mode
- 1 to enter in user take off.
- 0 to exit from user take off.
</arg>
</cmd>
<cmd name="Circle" id="9">
<comment
title="Circle"
desc="Make the fixed wing circle.\n
The circle will use the [CirclingAltitude](#1-6-14) and the [CirclingRadius](#1-6-13)"
support="090e"
result="The fixed wing will circle in the given direction.\n
Then, event [FlyingState](#1-4-1) is triggered with state set at hovering."/>
<expectations>
<immediate>
#1-4-1(state: hovering)
</immediate>
</expectations>
<arg name="direction" type="enum">
The circling direction
<enum name="CW">
Circling ClockWise
</enum>
<enum name="CCW">
Circling Counter ClockWise
</enum>
<enum name="default">
Use drone default Circling direction set by CirclingDirection cmd
</enum>
</arg>
</cmd>
<cmd name="moveTo" id="10">
<comment
title="Move to a location"
desc="Move the drone to a specified location.\n
If a new command moveTo is sent, the drone will immediatly run it (no cancel will be issued).\n
If a [CancelMoveTo](#1-0-11) command is sent, the moveTo is stopped.\n
During the moveTo, all pitch, roll and gaz values of the piloting command
will be ignored by the drone.\n
However, the yaw value can be used."
support="090c:4.3.0;0914;0919"
result="Event [MovingTo](#1-4-12) is triggered with state running.
Then, the drone will move to the given location.\n
Then, event [MoveToChanged](#1-4-12) is triggered with state succeed."/>
<expectations>
<immediate>
#1-4-12(latitude: this.latitude, longitude: this.longitude, altitude: this.altitude, orientation_mode: this.orientation_mode, status: RUNNING)
</immediate>
</expectations>
<arg name="latitude" type="double">
Latitude of the location (in degrees) to reach
</arg>
<arg name="longitude" type="double">
Longitude of the location (in degrees) to reach
</arg>
<arg name="altitude" type="double">
Altitude above take off point (in m) to reach
</arg>
<arg name="orientation_mode" type="enum">
Orientation mode of the move to
<enum name="NONE">
The drone won't change its orientation
</enum>
<enum name="TO_TARGET">
The drone will make a rotation to look in direction of the given location
</enum>
<enum name="HEADING_START">
The drone will orientate itself to the given heading before moving to the location
</enum>
<enum name="HEADING_DURING">
The drone will orientate itself to the given heading while moving to the location
</enum>
</arg>
<arg name="heading" type="float">
Heading (relative to the North in degrees).
This value is only used if the orientation mode is HEADING_START or HEADING_DURING
</arg>
</cmd>
<cmd name="CancelMoveTo" id="11">
<comment
title="Cancel the moveTo"
desc="Cancel the current moveTo.\n
If there is no current moveTo, this command has no effect."
support="090c:4.3.0"
result="Event [MoveToChanged](#1-4-12) is triggered with state canceled."/>
<expectations>
<immediate>
#1-4-12(status: CANCELED)
</immediate>
</expectations>
</cmd>
<cmd name="StartPilotedPOI" id="12" deprecated="true">
<comment
title="Start a piloted POI"
desc="Start a piloted Point Of Interest.\n
During a piloted POI, the drone will always look at the given POI but can be piloted normally.
However, yaw value is ignored. Camera tilt and pan command is also ignored.\n
Ignored if [PilotedPOI](#1-4-14) state is UNAVAILABLE."
support="090c:4.3.0"
result="If the drone is hovering, event [PilotedPOI](#1-4-14) is triggered with state RUNNING.
If the drone is not hovering, event [PilotedPOI](#1-4-14) is triggered with state PENDING,
waiting to hover. When the drone hovers, the state will change to RUNNING.
If the drone does not hover for a given time, piloted POI is canceled by the drone and state
will change to AVAILABLE.
Then, the drone will look at the given location."/>
<expectations>
<immediate>
#1-4-14(latitude: this.latitude, longitude: this.longitude, altitude: this.altitude, status: RUNNING)
|#1-4-14(latitude: this.latitude, longitude: this.longitude, altitude: this.altitude, status: PENDING)
</immediate>
</expectations>
<arg name="latitude" type="double">
Latitude of the location (in degrees) to look at
</arg>
<arg name="longitude" type="double">
Longitude of the location (in degrees) to look at
</arg>
<arg name="altitude" type="double">
Altitude above take off point (in m) to look at
</arg>
</cmd>
<cmd name="StartPilotedPOIV2" id="15">
<comment
title="Start a piloted POI"
desc="Start a piloted Point Of Interest.\n
During a piloted POI, the drone always points towards the given POI but can be piloted normally.
However, yaw value is ignored. The gimbal behavior depends on the mode argument:\n
- in locked gimbal mode, the gimbal always looks at the POI, and gimbal control command is ignored by
the drone,\n
- in free gimbal mode, the gimbal initially looks at the POI, and is then freely controllable by the
gimbal command.\n
Ignored if [PilotedPOIV2](#1-4-22) state is UNAVAILABLE."
support="0914:1.6.3;0919:1.6.3"
result="If the drone is hovering, event [PilotedPOIV2](#1-4-22) is triggered with state RUNNING.
If the drone is not hovering, event [PilotedPOIV2](#1-4-22) is triggered with state PENDING,
waiting to hover. When the drone hovers, the state changes to RUNNING.
If the drone does not hover for a given time, piloted POI is canceled by the drone and state
changes to AVAILABLE.
Then, the drone looks at the given location."/>
<expectations>
<immediate>
#1-4-22(latitude: this.latitude, longitude: this.longitude, altitude: this.altitude, mode: this.mode, status: RUNNING)
|#1-4-22(latitude: this.latitude, longitude: this.longitude, altitude: this.altitude, mode: this.mode, status: PENDING)
</immediate>
</expectations>
<arg name="latitude" type="double">
Latitude of the location (in degrees) to look at
</arg>
<arg name="longitude" type="double">
Longitude of the location (in degrees) to look at
</arg>
<arg name="altitude" type="double">
Altitude above take off point (in m) to look at
</arg>
<arg name="mode" type="enum">
POI mode
<enum name="locked_gimbal">
Gimbal is locked on the POI
</enum>
<enum name="locked_once_gimbal">
Gimbal is locked on the POI once, then it is freely controllable
</enum>
<enum name="free_gimbal">
Gimbal is freely controllable
</enum>
</arg>
</cmd>
<cmd name="StopPilotedPOI" id="13">
<comment
title="Stop the piloted POI"
desc="Stop the piloted Point Of Interest (with or without gimbal control).\n
If [PilotedPOI](#1-4-14) or [PilotedPOIV2](#1-4-22) state is RUNNING or PENDING, stop it."
support="090c:4.3.0;0914;0919"
result="Event [PilotedPOI](#1-4-14) or [PilotedPOIV2](#1-4-22) is triggered with state AVAILABLE."/>
<expectations>
<immediate>
#1-4-14(status: AVAILABLE)
|#1-4-22(status: AVAILABLE)
</immediate>
</expectations>
</cmd>
<cmd name="CancelMoveBy" id="14">
<comment
title="Cancel the relative move"
desc="Cancel the current relative move.\n
If there is no current relative move, this command has no effect."
result="Event [RelativeMoveChanged](#1-4-16) is triggered with state canceled."/>
</cmd>
<cmd name="SmartTakeOffLand" id="16">
<comment
title="Take off or land"
desc="Ask the drone to take off or land."
support="091a"
result="The drone takes off if its [FlyingState](#1-4-1) was landed.
The drone lands if its [FlyingState](#1-4-1) was taking off, hovering or flying.
Then, event [FlyingState](#1-4-1) is triggered."/>
<expectations>
<immediate>
#1-4-1(state: takingoff)
|#1-4-1(state: landing)
</immediate>
</expectations>
</cmd>
</class>
<class name="Animations" id="5">
Animation commands
<cmd name="Flip" id="0">
<comment
title="Make a flip"
desc="Make a flip."
support="0901;090c"
result="The drone will make a flip if it has enough battery."/>
<expectations>
<immediate>
#1-4-1(state: flying)
</immediate>
</expectations>
<arg name="direction" type="enum">
Direction for the flip
<enum name="front">
Flip direction front
</enum>
<enum name="back">
Flip direction back
</enum>
<enum name="right">
Flip direction right
</enum>
<enum name="left">
Flip direction left
</enum>
</arg>
</cmd>
</class>
<class name="Camera" id="1" deprecated="true">
Ask the drone to move camera
<cmd name="Orientation" id="0" buffer="NON_ACK" deprecated="true">
<comment
title="Move the camera"
desc="Move the camera.\n
You can get min and max values for tilt and pan using [CameraInfo](#0-15-0)."
support="0901;090c;090e"
result="The drone moves its camera.\n
Then, event [CameraOrientation](#1-25-0) is triggered."/>
<arg name="tilt" type="i8">
Tilt camera consign for the drone (in degree)
The value is saturated by the drone.
Saturation value is sent by thre drone through CameraSettingsChanged command.
</arg>
<arg name="pan" type="i8">
Pan camera consign for the drone (in degree)
The value is saturated by the drone.
Saturation value is sent by thre drone through CameraSettingsChanged command.
</arg>
</cmd>
<cmd name="OrientationV2" id="1" buffer="NON_ACK" deprecated="true">
<comment
title="Move the camera"
desc="Move the camera.\n
You can get min and max values for tilt and pan using [CameraInfo](#0-15-0)."
support="0901;090c;090e"
result="The drone moves its camera.\n
Then, event [CameraOrientationV2](#1-25-2) is triggered."/>
<arg name="tilt" type="float">
Tilt camera consign for the drone (in degree)
The value is saturated by the drone.
Saturation value is sent by thre drone through CameraSettingsChanged command.
</arg>
<arg name="pan" type="float">
Pan camera consign for the drone (in degree)
The value is saturated by the drone.
Saturation value is sent by thre drone through CameraSettingsChanged command.
</arg>
</cmd>
<cmd name="Velocity" id="2" buffer="NON_ACK" deprecated="true">
<comment
title="Move the camera using velocity"
desc="Move the camera given velocity consign.\n
You can get min and max values for tilt and pan using [CameraVelocityRange](#1-25-4)."
support="0901;090c;090e"
result="The drone moves its camera.\n
Then, event [CameraOrientationV2](#1-25-2) is triggered."/>
<arg name="tilt" type="float">
Tilt camera velocity consign [deg/s]
Negative tilt velocity move camera to bottom
Positive tilt velocity move camera to top
</arg>
<arg name="pan" type="float">
Pan camera velocity consign [deg/s]
Negative pan velocity move camera to left
Positive pan velocity move camera to right
</arg>
</cmd>
</class>
<class name="MediaRecord" id="7">
Media recording management
<cmd name="Picture" id="0" deprecated="true">
<comment
title="Take a picture"
desc="Take a picture."/>
<arg name="mass_storage_id" type="u8">
Mass storage id to take picture
</arg>
</cmd>
<cmd name="Video" id="1" deprecated="true">
<comment
title="Record a video"
desc="Record a video."/>
<arg name="record" type="enum">
Command to record video
<enum name="stop">
Stop the video recording
</enum>
<enum name="start">
Start the video recording
</enum>
</arg>
<arg name="mass_storage_id" type="u8">
Mass storage id to record
</arg>
</cmd>
<cmd name="PictureV2" id="2">
<comment
title="Take a picture"
desc="Take a picture.\n
The type of picture taken is related to the picture setting.\n
You can set the picture format by sending the command [SetPictureFormat](#1-19-0). You can also get the current picture format with [PictureFormat](#1-20-0).\n
Please note that the time required to take the picture is highly related to this format.\n\n
You can check if the picture taking is available with [PictureState](#1-8-2).\n
Also, please note that if your picture format is different from snapshot, picture taking will stop video recording (it will restart after that the picture has been taken)."
support="0901:2.0.1;090c;090e"
result="Event [PictureState](#1-8-2) will be triggered with a state busy.\n
The drone will take a picture.\n
Then, when picture has been taken, notification [PictureEvent](#1-3-0) is triggered.\n
And normally [PictureState](#1-8-2) will be triggered with a state ready."/>
<expectations>
<immediate>
#1-8-2(state: busy, error: ok)
</immediate>
</expectations>
</cmd>
<cmd name="VideoV2" id="3">
<comment
title="Record a video"
desc="Record a video (or start timelapse).\n
You can check if the video recording is available with [VideoState](#1-8-3).\n
This command can start a video (obvious huh?), but also a timelapse if the timelapse mode is set. You can check if the timelapse mode is set with the event [TimelapseMode](#1-20-4).\n
Also, please note that if your picture format is different from snapshot, picture taking will stop video recording (it will restart after the picture has been taken)."
support="0901:2.0.1;090c;090e"
result="The drone will begin or stop to record the video (or timelapse).\n
Then, event [VideoState](#1-8-3) will be triggered. Also, notification [VideoEvent](#1-3-1) is triggered."/>
<expectations>
<immediate>
#1-8-3(state: this.record, error: ok)
</immediate>
</expectations>
<arg name="record" type="enum">
Command to record video
<enum name="stop">
Stop the video recording
</enum>
<enum name="start">
Start the video recording
</enum>
</arg>
</cmd>
</class>
<class name="MediaRecordState" id="8">
State of media recording
<cmd name="PictureStateChanged" id="0" deprecated="true">
<comment
title="Picture state"
desc="Picture state."/>
<arg name="state" type="u8">
1 if picture has been taken, 0 otherwise
</arg>
<arg name="mass_storage_id" type="u8">
Mass storage id where the picture was recorded
</arg>
</cmd>
<cmd name="VideoStateChanged" id="1" deprecated="true">
<comment
title="Video record state"
desc="Picture record state."/>
<arg name="state" type="enum">
State of video
<enum name="stopped">
Video was stopped
</enum>
<enum name="started">
Video was started
</enum>
<enum name="failed">
Video was failed
</enum>
<enum name="autostopped">
Video was auto stopped
</enum>
</arg>
<arg name="mass_storage_id" type="u8">
Mass storage id where the video was recorded
</arg>
</cmd>
<cmd name="PictureStateChangedV2" id="2">
<comment
title="Picture state"
desc="Picture state."
support="0901:2.0.1;090c;090e"
triggered="by [TakePicture](#1-7-2) or by a change in the picture state"/>
<arg name="state" type="enum">
State of device picture recording
<enum name="ready">
The picture recording is ready
</enum>
<enum name="busy">
The picture recording is busy
</enum>
<enum name="notAvailable">
The picture recording is not available
</enum>
</arg>
<arg name="error" type="enum">
Error to explain the state
<enum name="ok">
No Error
</enum>
<enum name="unknown">
Unknown generic error
</enum>
<enum name="camera_ko">
Picture camera is out of order
</enum>
<enum name="memoryFull">
Memory full ; cannot save one additional picture
</enum>
<enum name="lowBattery">
Battery is too low to start/keep recording.
</enum>
</arg>
</cmd>
<cmd name="VideoStateChangedV2" id="3">
<comment
title="Video record state"
desc="Video record state."
support="0901:2.0.1;090c;090e"
triggered="by [RecordVideo](#1-7-3) or by a change in the video state"/>
<arg name="state" type="enum">
State of device video recording
<enum name="stopped">
Video is stopped
</enum>
<enum name="started">
Video is started
</enum>
<enum name="notAvailable">
The video recording is not available
</enum>
</arg>
<arg name="error" type="enum">
Error to explain the state
<enum name="ok">
No Error
</enum>
<enum name="unknown">
Unknown generic error
</enum>
<enum name="camera_ko">
Video camera is out of order
</enum>
<enum name="memoryFull">
Memory full ; cannot save one additional video
</enum>
<enum name="lowBattery">
Battery is too low to start/keep recording.
</enum>
</arg>
</cmd>
<cmd name="VideoResolutionState" id="4" deprecated="true">
<comment
title="Video resolution"
desc="Video resolution.\n
Informs about streaming and recording video resolutions.\n
Note that this is only an indication about what the resolution should be. To know the real resolution, you should get it from the frame."
support="none"
triggered="when the resolution changes."/>
<arg name="streaming" type="enum">
Streaming resolution
<enum name="res360p">
360p resolution.
</enum>
<enum name="res480p">
480p resolution.
</enum>
<enum name="res720p">
720p resolution.
</enum>
<enum name="res1080p">
1080p resolution.
</enum>
</arg>
<arg name="recording" type="enum">
Recording resolution
<enum name="res360p">
360p resolution.
</enum>
<enum name="res480p">
480p resolution.
</enum>
<enum name="res720p">
720p resolution.
</enum>
<enum name="res1080p">
1080p resolution.
</enum>
</arg>
</cmd>
</class>
<class name="MediaRecordEvent" id="3">
Events of media recording
<cmd name="PictureEventChanged" id="0" content="NOTIFICATION">
<comment
title="Picture taken"
desc="Picture taken.\n\n
**This event is a notification, you can't retrieve it in the cache of the device controller.**"
support="0901:2.0.1;090c;090e"
triggered="after a [TakePicture](#1-7-2), when the picture has been taken (or it has failed)."/>
<arg name="event" type="enum">
Last event of picture recording
<enum name="taken">
Picture taken and saved
</enum>
<enum name="failed">
Picture failed
</enum>
</arg>
<arg name="error" type="enum">
Error to explain the event
<enum name="ok">
No Error
</enum>
<enum name="unknown">
Unknown generic error ; only when state is failed
</enum>
<enum name="busy">
Picture recording is busy ; only when state is failed
</enum>
<enum name="notAvailable">
Picture recording not available ; only when state is failed
</enum>
<enum name="memoryFull">
Memory full ; only when state is failed
</enum>
<enum name="lowBattery">
Battery is too low to record.
</enum>
</arg>
</cmd>
<cmd name="VideoEventChanged" id="1" content="NOTIFICATION">
<comment
title="Video record notification"
desc="Video record notification.\n\n
**This event is a notification, you can't retrieve it in the cache of the device controller.**"
support="0901:2.0.1;090c;090e"
triggered="by [RecordVideo](#1-7-3) or a change in the video state."/>
<arg name="event" type="enum">
Event of video recording
<enum name="start">
Video start
</enum>
<enum name="stop">
Video stop and saved
</enum>
<enum name="failed">
Video failed
</enum>
</arg>
<arg name="error" type="enum">
Error to explain the event
<enum name="ok">
No Error
</enum>
<enum name="unknown">
Unknown generic error ; only when state is failed
</enum>
<enum name="busy">
Video recording is busy ; only when state is failed
</enum>
<enum name="notAvailable">
Video recording not available ; only when state is failed
</enum>
<enum name="memoryFull">
Memory full
</enum>
<enum name="lowBattery">
Battery is too low to record.
</enum>
<enum name="autoStopped">
Video was auto stopped
</enum>
</arg>
</cmd>
</class>
<class name="PilotingState" id="4">
State from drone
<cmd name="FlyingStateChanged" id="1">
<comment
title="Flying state"
desc="Flying state."
support="0901;090c;090e;0914;0919"
triggered="when the flying state changes."/>
<arg name="state" type="enum">
Drone flying state
<enum name="landed">
Landed state
</enum>
<enum name="takingoff">
Taking off state
</enum>
<enum name="hovering">
Hovering / Circling (for fixed wings) state
</enum>
<enum name="flying">
Flying state
</enum>
<enum name="landing">
Landing state
</enum>
<enum name="emergency">
Emergency state
</enum>
<enum name="usertakeoff">
User take off state. Waiting for user action to take off.
</enum>
<enum name="motor_ramping">
Motor ramping state.
</enum>
<enum name="emergency_landing">
Emergency landing state.
Drone autopilot has detected defective sensor(s).
Only Yaw argument in PCMD is taken into account.
All others flying commands are ignored.
</enum>
</arg>
</cmd>
<cmd name="AlertStateChanged" id="2" deprecated="true">
<comment
title="Alert state"
desc="Alert state."
support="0901;090c;090e;0914;0919"
triggered="when an alert happens on the drone."/>
<arg name="state" type="enum">
Drone alert state
<enum name="none">
No alert
</enum>
<enum name="user">
User emergency alert
</enum>
<enum name="cut_out">
Cut out alert
</enum>
<enum name="critical_battery">
Critical battery alert
</enum>
<enum name="low_battery">
Low battery alert
</enum>
<enum name="too_much_angle">
The angle of the drone is too high
</enum>
<enum name="almost_empty_battery">
Almost empty battery alert
</enum>
<enum name="magneto_pertubation">
Magnetometer is disturbed by a magnetic element
</enum>
<enum name="magneto_low_earth_field">
Local terrestrial magnetic field is too weak
</enum>
</arg>
</cmd>
<cmd name="NavigateHomeStateChanged" id="3" deprecated="true">
<comment
title="Return home state"
desc="Return home state.\n
Availability is related to gps fix, magnetometer calibration."
support="0901;090c;090e;0914;0919"
triggered="by [ReturnHome](#1-0-5) or when the state of the return home changes."/>
<arg name="state" type="enum">
State of navigate home
<enum name="available">
Navigate home is available
</enum>
<enum name="inProgress">
Navigate home is in progress
</enum>
<enum name="unavailable">
Navigate home is not available
</enum>
<enum name="pending">
Navigate home has been received, but its process is pending
</enum>
</arg>
<arg name="reason" type="enum">
Reason of the state
<enum name="userRequest">
User requested a navigate home (available->inProgress)
</enum>
<enum name="connectionLost">
Connection between controller and product lost (available->inProgress)
</enum>
<enum name="lowBattery">
Low battery occurred (available->inProgress)
</enum>
<enum name="finished">
Navigate home is finished (inProgress->available)
</enum>
<enum name="stopped">
Navigate home has been stopped (inProgress->available)
</enum>
<enum name="disabled">
Navigate home disabled by product (inProgress->unavailable or available->unavailable)
</enum>
<enum name="enabled">
Navigate home enabled by product (unavailable->available)
</enum>
<enum name="flightplan">
Return to home during a flightplan (available->in_progress)
</enum>
<enum name="icing">
Return to home triggered by propeller icing event (available->in_progress)
</enum>
</arg>
</cmd>
<cmd name="PositionChanged" id="4" buffer="NON_ACK" deprecated="true">
<comment
title="Drone's position changed"
desc="Drone's position changed."
support="0901;090c;090e;0914;0919"
triggered="regularly."/>
<arg name="latitude" type="double">
Latitude position in decimal degrees (500.0 if not available)
</arg>
<arg name="longitude" type="double">
Longitude position in decimal degrees (500.0 if not available)
</arg>
<arg name="altitude" type="double">
Altitude in meters (from GPS)
</arg>
</cmd>
<cmd name="SpeedChanged" id="5" buffer="NON_ACK">
<comment
title="Drone's speed changed"
desc="Drone's speed changed.\n
Expressed in the NED referential (North-East-Down)."
support="0901;090c;090e;0914;0919"
triggered="regularly."/>
<arg name="speedX" type="float">
Speed relative to the North (when drone moves to the north, speed is > 0) (in m/s)
</arg>
<arg name="speedY" type="float">
Speed relative to the East (when drone moves to the east, speed is > 0) (in m/s)
</arg>
<arg name="speedZ" type="float">
Speed on the z axis (when drone moves down, speed is > 0) (in m/s)
</arg>
</cmd>
<cmd name="AttitudeChanged" id="6" buffer="NON_ACK">
<comment
title="Drone's attitude changed"
desc="Drone's attitude changed."
support="0901;090c;090e;0914;0919"
triggered="regularly."/>
<arg name="roll" type="float">
roll value (in radian)
</arg>
<arg name="pitch" type="float">
Pitch value (in radian)
</arg>
<arg name="yaw" type="float">
Yaw value (in radian)
</arg>