Onboard-SDK-ROS
DJI_WayPoint.h
Go to the documentation of this file.
1 
19 #include "DJI_Mission.h"
20 
21 #ifndef DJI_WAYPOINT_H
22 #define DJI_WAYPOINT_H
23 
24 namespace DJI
25 {
26 namespace onboardSDK
27 {
28 
29 class WayPoint;
30 
31 #pragma pack(1)
32 typedef struct WayPointInitData
33 {
34  uint8_t indexNumber;
35  float32_t maxVelocity;
36  float32_t idleVelocity;
37 
38  uint8_t finishAction;
39  uint8_t executiveTimes;
40  uint8_t yawMode;
41  uint8_t traceMode;
42  uint8_t RCLostAction;
43  uint8_t gimbalPitch;
44  float64_t latitude;
45  float64_t longitude;
46  float32_t altitude;
47 
48  uint8_t reserved[16];
50 
51 typedef struct WayPointData
52 {
53  uint8_t index;
54 
55  float64_t latitude;
56  float64_t longitude;
57  float32_t altitude;
58  float32_t damping;
59 
60  int16_t yaw;
61  int16_t gimbalPitch;
62  uint8_t turnMode;
63 
64  uint8_t reserved[8];
65  uint8_t hasAction;
66  uint16_t actionTimeLimit;
67 
68  uint8_t actionNumber : 4;
69  uint8_t actionRepeat : 4;
70 
71  uint8_t commandList[16];
72  int16_t commandParameter[16];
73 } WayPointData;
74 
75 typedef struct WayPointVelocityACK
76 {
77  uint8_t ack;
78  float32_t idleVelocity;
80 
81 typedef struct WayPointInitACK
82 {
83  uint8_t ack;
84  WayPointInitData data;
86 
87 typedef struct WayPointDataACK
88 {
89  uint8_t ack;
90  uint8_t index;
92 
93 #pragma pack()
94 
95 class WayPoint
96 {
97  public:
98 #ifndef STATIC_MEMORY
99  WayPoint(CoreAPI *ControlAPI = 0);
100 #else
101  WayPoint(WayPointData *list, uint8_t len, CoreAPI *ControlAPI = 0);
102 #endif // STATIC_MEMORY
103  void init(WayPointInitData *Info = 0, CallBack callback = 0, UserData userData = 0);
104  void start(CallBack callback = 0, UserData userData = 0);
105  void stop(CallBack callback = 0, UserData userData = 0);
107  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
108  void readInitData(CallBack callback = 0, UserData userData = 0);
109  void readIndexData(uint8_t index, CallBack callback = 0, UserData userData = 0);
110  void readIdleVelocity(CallBack callback = 0, UserData userData = 0);
112  //void uploadAll(CallBack callback = 0, UserData userData = 0);
113  bool uploadIndexData(WayPointData *data, CallBack callback = 0, UserData userData = 0);
114  bool uploadIndexData(uint8_t pos, CallBack callback = 0, UserData userData = 0);
115  void updateIdleVelocity(float32_t meterPreSecond, CallBack callback = 0,
116  UserData userData = 0);
117 
118  void setInfo(const WayPointInitData &value);
119  void setIndex(WayPointData *value, size_t pos);
120  WayPointInitData getInfo() const;
121  WayPointData *getIndex() const;
122  WayPointData *getIndex(size_t pos) const;
123 
124  public:
125  static void idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
126  static void readInitDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
127  static void uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
130 
131  private:
132  CoreAPI *api;
133  WayPointInitData info;
134  WayPointData *index;
135 #ifdef STATIC_MEMORY
136  uint8_t maxIndex;
137 #endif // STATIC_MEMORY
138 };
139 
140 } // namespace onboardSDK
141 } // namespace DJI
142 
143 #endif // DJI_WAYPOINT_H
Definition: DJI_WayPoint.h:95
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
Definition: DJI_WayPoint.h:51
Definition: DJI_WayPoint.h:87
Definition: DJI_Type.h:118
Definition: DJI_WayPoint.h:81
Definition: DJI_WayPoint.h:75
Definition: DJI_Mission.cpp:16
float32_t altitude
not supported yet
Definition: DJI_WayPoint.h:46
float64_t longitude
Definition: DJI_WayPoint.h:45
Definition: DJI_WayPoint.h:32