dji_mobile_communication.hpp
Go to the documentation of this file.
1 
29 #ifndef MOC_H
30 #define MOC_H
31 
32 #include "dji_macros.hpp"
33 #include "dji_vehicle_callback.hpp"
34 
35 namespace DJI
36 {
37 namespace OSDK
38 {
39 
40 // Forward Declarations
41 class Vehicle;
42 
54 {
55 public:
56  MobileCommunication(Vehicle* vehicle = 0);
58 
59  Vehicle* getVehicle() const;
60  void setVehicle(Vehicle* value);
61 
62 public:
69  void sendDataToMSDK(uint8_t* data, uint8_t len);
70  static void getDataFromMSDKCallback(Vehicle* vehiclePtr,
71  RecvContainer recvFrame,
72  UserData userData);
73 
74 public:
75  VehicleCallBackHandler fromMSDKHandler;
76  void setFromMSDKCallback(VehicleCallBack callback, UserData userData = 0);
77 
78 private:
79  Vehicle* vehicle;
80 };
81 
82 } // OSDK
83 } // DJI
84 
85 #endif // MOC_H
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: dji_type.hpp:75
Type definition for new Vehicle-style callbacks.
A top-level encapsulation of a DJI drone/FC connected to your OES.
Definition: dji_vehicle.hpp:93
void(* VehicleCallBack)(Vehicle *vehicle, RecvContainer recvFrame, UserData userData)
Function prototype for all callback functions used in the OSDK.
Definition: dji_vehicle_callback.hpp:49
APIs for Mobile-Onboard SDK Communication.
Definition: dji_mobile_communication.hpp:53
void sendDataToMSDK(uint8_t *data, uint8_t len)
sending data from OSDK to MSDK
Definition: dji_mobile_communication.cpp:61
The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.
Definition: dji_vehicle_callback.hpp:56
Definition: dji_ack.cpp:39