Classes | Public Types | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes
DJIDrone Class Reference

#include <dji_drone.h>

List of all members.

Classes

struct  CallBackHandler

Public Types

typedef void(* CallBack )(DJIDrone *)
typedef struct
DJIDrone::CallBackHandler 
CallBackHandler
typedef void * UserData

Public Member Functions

bool activate ()
bool attitude_control (unsigned char ctrl_flag, float x, float y, float z, float yaw)
bool check_version ()
 DJIDrone (ros::NodeHandle &nh)
bool drone_arm ()
bool drone_disarm ()
bool gimbal_angle_control (int roll=0, int pitch=0, int yaw=0, int duration=0, bool absolute_or_incremental=1, bool yaw_cmd_ignore=0, bool roll_cmd_ignore=0, bool pitch_cmd_ignore=0)
bool gimbal_speed_control (int roll_rate=0, int pitch_rate=0, int yaw_rate=0)
bool global_position_control (double latitude, double longitude, float altitude, float yaw)
void global_position_navigation_cancel_all_goals ()
void global_position_navigation_cancel_current_goal ()
void global_position_navigation_cancel_goals_at_and_before_time (const ros::Time time)
dji_sdk::GlobalPositionNavigationResultConstPtr global_position_navigation_get_result ()
actionlib::SimpleClientGoalState global_position_navigation_get_state ()
bool global_position_navigation_is_server_connected ()
void global_position_navigation_send_request (double latitude, double longitude, float altitude, GlobalPositionNavigationActionClient::SimpleDoneCallback done_callback=GlobalPositionNavigationActionClient::SimpleDoneCallback(), GlobalPositionNavigationActionClient::SimpleActiveCallback active_callback=GlobalPositionNavigationActionClient::SimpleActiveCallback(), GlobalPositionNavigationActionClient::SimpleFeedbackCallback feedback_callback=GlobalPositionNavigationActionClient::SimpleFeedbackCallback())
bool global_position_navigation_stop_tracking_goal ()
bool global_position_navigation_wait_for_result (const ros::Duration duration=ros::Duration(0))
bool global_position_navigation_wait_server (const ros::Duration duration=ros::Duration(0))
bool gohome ()
bool landing ()
bool local_position_control (float x, float y, float z, float yaw)
void local_position_navigation_cancel_all_goals ()
void local_position_navigation_cancel_current_goal ()
void local_position_navigation_cancel_goals_at_and_before_time (const ros::Time time)
dji_sdk::LocalPositionNavigationResultConstPtr local_position_navigation_get_result ()
actionlib::SimpleClientGoalState local_position_navigation_get_state ()
bool local_position_navigation_is_server_connected ()
void local_position_navigation_send_request (float x, float y, float z, LocalPositionNavigationActionClient::SimpleDoneCallback done_callback=LocalPositionNavigationActionClient::SimpleDoneCallback(), LocalPositionNavigationActionClient::SimpleActiveCallback active_callback=LocalPositionNavigationActionClient::SimpleActiveCallback(), LocalPositionNavigationActionClient::SimpleFeedbackCallback feedback_callback=LocalPositionNavigationActionClient::SimpleFeedbackCallback())
bool local_position_navigation_stop_tracking_goal ()
bool local_position_navigation_wait_for_result (const ros::Duration duration=ros::Duration(0))
bool local_position_navigation_wait_server (const ros::Duration duration=ros::Duration(0))
bool mission_cancel ()
bool mission_followme_update_target (dji_sdk::MissionFollowmeTarget followme_target)
bool mission_followme_upload (dji_sdk::MissionFollowmeTask followme_task)
dji_sdk::MissionHotpointTask mission_hotpoint_download ()
bool mission_hotpoint_reset_yaw ()
bool mission_hotpoint_set_radius (float radius)
bool mission_hotpoint_set_speed (float speed, uint8_t direction)
bool mission_hotpoint_upload (dji_sdk::MissionHotpointTask hotpoint_task)
bool mission_pause ()
bool mission_resume ()
bool mission_start ()
dji_sdk::MissionWaypointTask mission_waypoint_download ()
float mission_waypoint_get_speed ()
bool mission_waypoint_set_speed (float speed)
bool mission_waypoint_upload (dji_sdk::MissionWaypointTask waypoint_task)
bool release_sdk_permission_control ()
bool request_sdk_permission_control ()
bool sdk_permission_control (unsigned char request)
bool set_message_frequency (uint8_t frequency_data[16])
void setArmMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setAttitudeControlDemoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setDisarmMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setDrawCircleDemoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setDrawSquareDemoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setGetSDKVersionMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setGimbalControlDemoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setGlobalNavigationTestMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setGoHomeMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setLandingMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setLocalNavigationTestMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setObtainControlMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setReleaseControlMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setStartCollisionAvoidanceCallback (DJIDrone::CallBack userCallback, UserData userData)
void setStartMapLASLoggingMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setStartVideoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setStopCollisionAvoidanceCallback (DJIDrone::CallBack userCallback, UserData userData)
void setStopMapLASLoggingMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setStopVideoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setTakeOffMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setTakePhotoMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setVirtuaRCTestMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
void setWaypointNavigationTestMobileCallback (DJIDrone::CallBack userCallback, UserData userData)
bool start_video ()
bool stop_video ()
bool sync_flag_control (float frequency)
bool take_picture ()
bool takeoff ()
bool velocity_control (int frame, float x, float y, float z, float yaw)
bool virtual_rc_control (uint32_t channel_data[16])
bool virtual_rc_disable ()
bool virtual_rc_enable ()
void waypoint_navigation_cancel_all_goals ()
void waypoint_navigation_cancel_current_goal ()
void waypoint_navigation_cancel_goals_at_and_before_time (const ros::Time time)
dji_sdk::WaypointNavigationResultConstPtr waypoint_navigation_get_result ()
actionlib::SimpleClientGoalState waypoint_navigation_get_state ()
bool waypoint_navigation_is_server_connected ()
void waypoint_navigation_send_request (dji_sdk::WaypointList waypoint_data, WaypointNavigationActionClient::SimpleDoneCallback done_callback=WaypointNavigationActionClient::SimpleDoneCallback(), WaypointNavigationActionClient::SimpleActiveCallback active_callback=WaypointNavigationActionClient::SimpleActiveCallback(), WaypointNavigationActionClient::SimpleFeedbackCallback feedback_callback=WaypointNavigationActionClient::SimpleFeedbackCallback())
bool waypoint_navigation_stop_tracking_goal ()
bool waypoint_navigation_wait_for_result (const ros::Duration duration=ros::Duration(0))
bool waypoint_navigation_wait_server (const ros::Duration duration=ros::Duration(0))

Public Attributes

dji_sdk::Acceleration acceleration
bool activation = false
dji_sdk::AttitudeQuaternion attitude_quaternion
dji_sdk::Compass compass
dji_sdk::FlightControlInfo flight_control_info
uint8_t flight_status
dji_sdk::MissionStatusFollowme followme_mission_push_info
dji_sdk::Gimbal gimbal
dji_sdk::GlobalPosition global_position
dji_sdk::GlobalPosition global_position_ref
dji_sdk::MissionStatusHotpoint hotpoint_mission_push_info
uint8_t incident_type
dji_sdk::LocalPosition local_position
dji_sdk::LocalPosition local_position_ref
bool localposbase_use_height = true
uint8_t mission_type
dji_sdk::TransparentTransmissionData mobile_data
uint8_t mobile_new_data
nav_msgs::Odometry odometry
dji_sdk::MissionStatusOther other_mission_push_info
dji_sdk::PowerStatus power_status
dji_sdk::RCChannels rc_channels
dji_sdk::TimeStamp time_stamp
dji_sdk::Velocity velocity
dji_sdk::MissionEventWpAction waypoint_action_result
dji_sdk::MissionStatusWaypoint waypoint_mission_push_info
dji_sdk::MissionEventWpReach waypoint_reached_result
dji_sdk::MissionEventWpUpload waypoint_upload_result

Private Types

typedef
actionlib::SimpleActionClient
< dji_sdk::DroneTaskAction > 
DroneTaskActionClient
typedef
actionlib::SimpleActionClient
< dji_sdk::GlobalPositionNavigationAction > 
GlobalPositionNavigationActionClient
typedef
actionlib::SimpleActionClient
< dji_sdk::LocalPositionNavigationAction > 
LocalPositionNavigationActionClient
typedef
actionlib::SimpleActionClient
< dji_sdk::WaypointNavigationAction > 
WaypointNavigationActionClient

Private Member Functions

void acceleration_subscriber_callback (dji_sdk::Acceleration acceleration)
void activation_subscriber_callback (std_msgs::UInt8 activation)
void attitude_quaternion_subscriber_callback (dji_sdk::AttitudeQuaternion attitude_quaternion)
void compass_subscriber_callback (dji_sdk::Compass compass)
void flight_control_info_subscriber_callback (dji_sdk::FlightControlInfo flight_control_info)
void flight_status_subscriber_callback (std_msgs::UInt8 flight_status)
void gimbal_subscriber_callback (dji_sdk::Gimbal gimbal)
void global_position_subscriber_callback (dji_sdk::GlobalPosition global_position)
void local_position_subscriber_callback (dji_sdk::LocalPosition local_position)
void mission_event_push_info_callback (dji_sdk::MissionPushInfo event_push_info)
void mission_status_push_info_callback (dji_sdk::MissionPushInfo status_push_info)
void mobile_data_push_info_callback (dji_sdk::TransparentTransmissionData information)
void odometry_subscriber_callback (nav_msgs::Odometry odometry)
void power_status_subscriber_callback (dji_sdk::PowerStatus power_status)
void rc_channels_subscriber_callback (dji_sdk::RCChannels rc_channels)
void time_stamp_subscriber_callback (dji_sdk::TimeStamp time_stamp)
void velocity_subscriber_callback (dji_sdk::Velocity velocity)

Private Attributes

ros::Subscriber acceleration_subscriber
ros::ServiceClient activation_service
ros::Subscriber activation_subscriber
CallBackHandler armCallback
ros::ServiceClient attitude_control_service
ros::Subscriber attitude_quaternion_subscriber
CallBackHandler attitudeControlDemoCallback
ros::ServiceClient camera_action_control_service
ros::Subscriber compass_subscriber
CallBackHandler disArmCallback
CallBackHandler drawCircleDemoCallback
CallBackHandler drawSquareDemoCallback
ros::ServiceClient drone_arm_control_service
DroneTaskActionClient drone_task_action_client
ros::ServiceClient drone_task_control_service
ros::Subscriber flight_control_info_subscriber
ros::Subscriber flight_status_subscriber
CallBackHandler getSDKVersionCallback
ros::ServiceClient gimbal_angle_control_service
ros::ServiceClient gimbal_speed_control_service
ros::Subscriber gimbal_subscriber
CallBackHandler gimbalControlDemoCallback
ros::ServiceClient global_position_control_service
GlobalPositionNavigationActionClient global_position_navigation_action_client
ros::Subscriber global_position_subscriber
CallBackHandler globalNavigationTestCallback
CallBackHandler goHomeCallback
CallBackHandler landingCallback
ros::ServiceClient local_position_control_service
LocalPositionNavigationActionClient local_position_navigation_action_client
ros::Subscriber local_position_subscriber
CallBackHandler localNavigationTestCallback
ros::ServiceClient message_frequency_control_service
ros::ServiceClient mission_cancel_service
ros::Subscriber mission_event_subscriber
ros::ServiceClient mission_fm_set_target_service
ros::ServiceClient mission_fm_upload_service
ros::ServiceClient mission_hp_download_service
ros::ServiceClient mission_hp_reset_yaw_service
ros::ServiceClient mission_hp_set_radius_service
ros::ServiceClient mission_hp_set_speed_service
ros::ServiceClient mission_hp_upload_service
ros::ServiceClient mission_pause_service
ros::ServiceClient mission_start_service
ros::Subscriber mission_status_subscriber
ros::ServiceClient mission_wp_download_service
ros::ServiceClient mission_wp_get_speed_service
ros::ServiceClient mission_wp_set_speed_service
ros::ServiceClient mission_wp_upload_service
ros::Subscriber mobile_data_subscriber
CallBackHandler obtainControlCallback
 Callback Handler functions for Mobile data commands.
ros::Subscriber odometry_subscriber
ros::Subscriber power_status_subscriber
ros::Subscriber rc_channels_subscriber
CallBackHandler releaseControlCallback
ros::ServiceClient sdk_permission_control_service
CallBackHandler startCollisionAvoidanceCallback
CallBackHandler startMapLASLoggingCallback
CallBackHandler startVideoCallback
CallBackHandler stopCollisionAvoidanceCallback
CallBackHandler stopMapLASLoggingCallback
CallBackHandler stopVideoCallback
ros::ServiceClient sync_flag_control_service
CallBackHandler takeOffCallback
CallBackHandler takePhotoCallback
ros::Subscriber time_stamp_subscriber
ros::ServiceClient velocity_control_service
ros::Subscriber velocity_subscriber
ros::ServiceClient version_check_service
ros::ServiceClient virtual_rc_data_control_service
ros::ServiceClient virtual_rc_enable_control_service
CallBackHandler virtualRCTestCallback
WaypointNavigationActionClient waypoint_navigation_action_client
CallBackHandler waypointNavigationTestCallback

Detailed Description

Definition at line 22 of file dji_drone.h.


Member Typedef Documentation

typedef void(* DJIDrone::CallBack)(DJIDrone *)

Definition at line 124 of file dji_drone.h.

typedef actionlib::SimpleActionClient<dji_sdk::DroneTaskAction> DJIDrone::DroneTaskActionClient [private]

Definition at line 26 of file dji_drone.h.

typedef actionlib::SimpleActionClient<dji_sdk::GlobalPositionNavigationAction> DJIDrone::GlobalPositionNavigationActionClient [private]

Definition at line 28 of file dji_drone.h.

typedef actionlib::SimpleActionClient<dji_sdk::LocalPositionNavigationAction> DJIDrone::LocalPositionNavigationActionClient [private]

Definition at line 27 of file dji_drone.h.

typedef void* DJIDrone::UserData

Definition at line 123 of file dji_drone.h.

typedef actionlib::SimpleActionClient<dji_sdk::WaypointNavigationAction> DJIDrone::WaypointNavigationActionClient [private]

Definition at line 29 of file dji_drone.h.


Constructor & Destructor Documentation

DJIDrone::DJIDrone ( ros::NodeHandle nh) [inline]

Definition at line 469 of file dji_drone.h.


Member Function Documentation

void DJIDrone::acceleration_subscriber_callback ( dji_sdk::Acceleration  acceleration) [inline, private]

Definition at line 133 of file dji_drone.h.

bool DJIDrone::activate ( ) [inline]

Definition at line 674 of file dji_drone.h.

void DJIDrone::activation_subscriber_callback ( std_msgs::UInt8  activation) [inline, private]

Definition at line 188 of file dji_drone.h.

bool DJIDrone::attitude_control ( unsigned char  ctrl_flag,
float  x,
float  y,
float  z,
float  yaw 
) [inline]

Definition at line 772 of file dji_drone.h.

void DJIDrone::attitude_quaternion_subscriber_callback ( dji_sdk::AttitudeQuaternion  attitude_quaternion) [inline, private]

Definition at line 138 of file dji_drone.h.

bool DJIDrone::check_version ( ) [inline]

Definition at line 680 of file dji_drone.h.

void DJIDrone::compass_subscriber_callback ( dji_sdk::Compass  compass) [inline, private]

Definition at line 143 of file dji_drone.h.

bool DJIDrone::drone_arm ( ) [inline]

Definition at line 826 of file dji_drone.h.

bool DJIDrone::drone_disarm ( ) [inline]

Definition at line 833 of file dji_drone.h.

void DJIDrone::flight_control_info_subscriber_callback ( dji_sdk::FlightControlInfo  flight_control_info) [inline, private]

Definition at line 148 of file dji_drone.h.

void DJIDrone::flight_status_subscriber_callback ( std_msgs::UInt8  flight_status) [inline, private]

Definition at line 153 of file dji_drone.h.

bool DJIDrone::gimbal_angle_control ( int  roll = 0,
int  pitch = 0,
int  yaw = 0,
int  duration = 0,
bool  absolute_or_incremental = 1,
bool  yaw_cmd_ignore = 0,
bool  roll_cmd_ignore = 0,
bool  pitch_cmd_ignore = 0 
) [inline]

Definition at line 738 of file dji_drone.h.

bool DJIDrone::gimbal_speed_control ( int  roll_rate = 0,
int  pitch_rate = 0,
int  yaw_rate = 0 
) [inline]

Definition at line 728 of file dji_drone.h.

void DJIDrone::gimbal_subscriber_callback ( dji_sdk::Gimbal  gimbal) [inline, private]

Definition at line 158 of file dji_drone.h.

bool DJIDrone::global_position_control ( double  latitude,
double  longitude,
float  altitude,
float  yaw 
) [inline]

Definition at line 871 of file dji_drone.h.

Definition at line 945 of file dji_drone.h.

Definition at line 940 of file dji_drone.h.

Definition at line 950 of file dji_drone.h.

dji_sdk::GlobalPositionNavigationResultConstPtr DJIDrone::global_position_navigation_get_result ( ) [inline]

Definition at line 955 of file dji_drone.h.

Definition at line 960 of file dji_drone.h.

Definition at line 965 of file dji_drone.h.

Definition at line 970 of file dji_drone.h.

Definition at line 987 of file dji_drone.h.

Definition at line 982 of file dji_drone.h.

Definition at line 993 of file dji_drone.h.

void DJIDrone::global_position_subscriber_callback ( dji_sdk::GlobalPosition  global_position) [inline, private]

Definition at line 163 of file dji_drone.h.

bool DJIDrone::gohome ( ) [inline]

Definition at line 700 of file dji_drone.h.

bool DJIDrone::landing ( ) [inline]

Definition at line 693 of file dji_drone.h.

bool DJIDrone::local_position_control ( float  x,
float  y,
float  z,
float  yaw 
) [inline]

Definition at line 859 of file dji_drone.h.

Definition at line 887 of file dji_drone.h.

Definition at line 882 of file dji_drone.h.

Definition at line 892 of file dji_drone.h.

dji_sdk::LocalPositionNavigationResultConstPtr DJIDrone::local_position_navigation_get_result ( ) [inline]

Definition at line 897 of file dji_drone.h.

Definition at line 902 of file dji_drone.h.

Definition at line 907 of file dji_drone.h.

Definition at line 912 of file dji_drone.h.

Definition at line 929 of file dji_drone.h.

Definition at line 924 of file dji_drone.h.

Definition at line 935 of file dji_drone.h.

void DJIDrone::local_position_subscriber_callback ( dji_sdk::LocalPosition  local_position) [inline, private]

Definition at line 168 of file dji_drone.h.

bool DJIDrone::mission_cancel ( ) [inline]

Definition at line 1075 of file dji_drone.h.

void DJIDrone::mission_event_push_info_callback ( dji_sdk::MissionPushInfo  event_push_info) [inline, private]

Definition at line 444 of file dji_drone.h.

bool DJIDrone::mission_followme_update_target ( dji_sdk::MissionFollowmeTarget  followme_target) [inline]

Definition at line 1151 of file dji_drone.h.

bool DJIDrone::mission_followme_upload ( dji_sdk::MissionFollowmeTask  followme_task) [inline]

Definition at line 1144 of file dji_drone.h.

dji_sdk::MissionHotpointTask DJIDrone::mission_hotpoint_download ( ) [inline]

Definition at line 1116 of file dji_drone.h.

Definition at line 1138 of file dji_drone.h.

bool DJIDrone::mission_hotpoint_set_radius ( float  radius) [inline]

Definition at line 1131 of file dji_drone.h.

bool DJIDrone::mission_hotpoint_set_speed ( float  speed,
uint8_t  direction 
) [inline]

Definition at line 1123 of file dji_drone.h.

bool DJIDrone::mission_hotpoint_upload ( dji_sdk::MissionHotpointTask  hotpoint_task) [inline]

Definition at line 1109 of file dji_drone.h.

bool DJIDrone::mission_pause ( ) [inline]

Definition at line 1061 of file dji_drone.h.

bool DJIDrone::mission_resume ( ) [inline]

Definition at line 1068 of file dji_drone.h.

bool DJIDrone::mission_start ( ) [inline]

Definition at line 1055 of file dji_drone.h.

void DJIDrone::mission_status_push_info_callback ( dji_sdk::MissionPushInfo  status_push_info) [inline, private]

Definition at line 203 of file dji_drone.h.

dji_sdk::MissionWaypointTask DJIDrone::mission_waypoint_download ( ) [inline]

Definition at line 1088 of file dji_drone.h.

Definition at line 1102 of file dji_drone.h.

bool DJIDrone::mission_waypoint_set_speed ( float  speed) [inline]

Definition at line 1095 of file dji_drone.h.

bool DJIDrone::mission_waypoint_upload ( dji_sdk::MissionWaypointTask  waypoint_task) [inline]

Definition at line 1081 of file dji_drone.h.

void DJIDrone::mobile_data_push_info_callback ( dji_sdk::TransparentTransmissionData  information) [inline, private]

Definition at line 266 of file dji_drone.h.

void DJIDrone::odometry_subscriber_callback ( nav_msgs::Odometry  odometry) [inline, private]

Definition at line 193 of file dji_drone.h.

void DJIDrone::power_status_subscriber_callback ( dji_sdk::PowerStatus  power_status) [inline, private]

Definition at line 173 of file dji_drone.h.

void DJIDrone::rc_channels_subscriber_callback ( dji_sdk::RCChannels  rc_channels) [inline, private]

Definition at line 178 of file dji_drone.h.

Definition at line 758 of file dji_drone.h.

Definition at line 753 of file dji_drone.h.

bool DJIDrone::sdk_permission_control ( unsigned char  request) [inline]

Definition at line 763 of file dji_drone.h.

bool DJIDrone::set_message_frequency ( uint8_t  frequency_data[16]) [inline]

Definition at line 847 of file dji_drone.h.

void DJIDrone::setArmMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 561 of file dji_drone.h.

void DJIDrone::setAttitudeControlDemoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 614 of file dji_drone.h.

void DJIDrone::setDisarmMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 567 of file dji_drone.h.

void DJIDrone::setDrawCircleDemoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 602 of file dji_drone.h.

void DJIDrone::setDrawSquareDemoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 608 of file dji_drone.h.

void DJIDrone::setGetSDKVersionMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 554 of file dji_drone.h.

void DJIDrone::setGimbalControlDemoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 644 of file dji_drone.h.

void DJIDrone::setGlobalNavigationTestMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 626 of file dji_drone.h.

void DJIDrone::setGoHomeMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 575 of file dji_drone.h.

void DJIDrone::setLandingMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 547 of file dji_drone.h.

void DJIDrone::setLocalNavigationTestMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 620 of file dji_drone.h.

void DJIDrone::setObtainControlMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 527 of file dji_drone.h.

void DJIDrone::setReleaseControlMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 534 of file dji_drone.h.

void DJIDrone::setStartCollisionAvoidanceCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 662 of file dji_drone.h.

void DJIDrone::setStartMapLASLoggingMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 650 of file dji_drone.h.

void DJIDrone::setStartVideoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 589 of file dji_drone.h.

void DJIDrone::setStopCollisionAvoidanceCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 668 of file dji_drone.h.

void DJIDrone::setStopMapLASLoggingMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 656 of file dji_drone.h.

void DJIDrone::setStopVideoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 596 of file dji_drone.h.

void DJIDrone::setTakeOffMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 540 of file dji_drone.h.

void DJIDrone::setTakePhotoMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 582 of file dji_drone.h.

void DJIDrone::setVirtuaRCTestMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 638 of file dji_drone.h.

void DJIDrone::setWaypointNavigationTestMobileCallback ( DJIDrone::CallBack  userCallback,
UserData  userData 
) [inline]

Definition at line 632 of file dji_drone.h.

bool DJIDrone::start_video ( ) [inline]

Definition at line 714 of file dji_drone.h.

bool DJIDrone::stop_video ( ) [inline]

Definition at line 721 of file dji_drone.h.

bool DJIDrone::sync_flag_control ( float  frequency) [inline]

Definition at line 840 of file dji_drone.h.

bool DJIDrone::take_picture ( ) [inline]

Definition at line 707 of file dji_drone.h.

bool DJIDrone::takeoff ( ) [inline]

Definition at line 686 of file dji_drone.h.

void DJIDrone::time_stamp_subscriber_callback ( dji_sdk::TimeStamp  time_stamp) [inline, private]

Definition at line 198 of file dji_drone.h.

bool DJIDrone::velocity_control ( int  frame,
float  x,
float  y,
float  z,
float  yaw 
) [inline]

Definition at line 784 of file dji_drone.h.

void DJIDrone::velocity_subscriber_callback ( dji_sdk::Velocity  velocity) [inline, private]

Definition at line 183 of file dji_drone.h.

bool DJIDrone::virtual_rc_control ( uint32_t  channel_data[16]) [inline]

Definition at line 814 of file dji_drone.h.

bool DJIDrone::virtual_rc_disable ( ) [inline]

Definition at line 805 of file dji_drone.h.

bool DJIDrone::virtual_rc_enable ( ) [inline]

Definition at line 796 of file dji_drone.h.

Definition at line 1004 of file dji_drone.h.

Definition at line 999 of file dji_drone.h.

Definition at line 1009 of file dji_drone.h.

dji_sdk::WaypointNavigationResultConstPtr DJIDrone::waypoint_navigation_get_result ( ) [inline]

Definition at line 1014 of file dji_drone.h.

Definition at line 1019 of file dji_drone.h.

Definition at line 1024 of file dji_drone.h.

Definition at line 1029 of file dji_drone.h.

Definition at line 1044 of file dji_drone.h.

Definition at line 1039 of file dji_drone.h.

Definition at line 1050 of file dji_drone.h.


Member Data Documentation

dji_sdk::Acceleration DJIDrone::acceleration

Definition at line 90 of file dji_drone.h.

Definition at line 69 of file dji_drone.h.

bool DJIDrone::activation = false

Definition at line 107 of file dji_drone.h.

Definition at line 36 of file dji_drone.h.

Definition at line 80 of file dji_drone.h.

Definition at line 246 of file dji_drone.h.

Definition at line 37 of file dji_drone.h.

dji_sdk::AttitudeQuaternion DJIDrone::attitude_quaternion

Definition at line 91 of file dji_drone.h.

Definition at line 70 of file dji_drone.h.

Definition at line 254 of file dji_drone.h.

Definition at line 38 of file dji_drone.h.

dji_sdk::Compass DJIDrone::compass

Definition at line 92 of file dji_drone.h.

Definition at line 71 of file dji_drone.h.

Definition at line 247 of file dji_drone.h.

Definition at line 252 of file dji_drone.h.

Definition at line 253 of file dji_drone.h.

Definition at line 50 of file dji_drone.h.

Definition at line 31 of file dji_drone.h.

Definition at line 39 of file dji_drone.h.

dji_sdk::FlightControlInfo DJIDrone::flight_control_info

Definition at line 93 of file dji_drone.h.

Definition at line 72 of file dji_drone.h.

Definition at line 94 of file dji_drone.h.

Definition at line 73 of file dji_drone.h.

dji_sdk::MissionStatusFollowme DJIDrone::followme_mission_push_info

Definition at line 116 of file dji_drone.h.

Definition at line 245 of file dji_drone.h.

dji_sdk::Gimbal DJIDrone::gimbal

Definition at line 96 of file dji_drone.h.

Definition at line 40 of file dji_drone.h.

Definition at line 41 of file dji_drone.h.

Definition at line 74 of file dji_drone.h.

Definition at line 259 of file dji_drone.h.

dji_sdk::GlobalPosition DJIDrone::global_position

Definition at line 97 of file dji_drone.h.

Definition at line 42 of file dji_drone.h.

Definition at line 33 of file dji_drone.h.

dji_sdk::GlobalPosition DJIDrone::global_position_ref

Definition at line 98 of file dji_drone.h.

Definition at line 75 of file dji_drone.h.

Definition at line 257 of file dji_drone.h.

Definition at line 248 of file dji_drone.h.

dji_sdk::MissionStatusHotpoint DJIDrone::hotpoint_mission_push_info

Definition at line 115 of file dji_drone.h.

Definition at line 112 of file dji_drone.h.

Definition at line 244 of file dji_drone.h.

dji_sdk::LocalPosition DJIDrone::local_position

Definition at line 99 of file dji_drone.h.

Definition at line 43 of file dji_drone.h.

Definition at line 32 of file dji_drone.h.

dji_sdk::LocalPosition DJIDrone::local_position_ref

Definition at line 100 of file dji_drone.h.

Definition at line 76 of file dji_drone.h.

Definition at line 256 of file dji_drone.h.

Definition at line 108 of file dji_drone.h.

Definition at line 52 of file dji_drone.h.

Definition at line 55 of file dji_drone.h.

Definition at line 85 of file dji_drone.h.

Definition at line 66 of file dji_drone.h.

Definition at line 65 of file dji_drone.h.

Definition at line 61 of file dji_drone.h.

Definition at line 64 of file dji_drone.h.

Definition at line 63 of file dji_drone.h.

Definition at line 62 of file dji_drone.h.

Definition at line 60 of file dji_drone.h.

Definition at line 54 of file dji_drone.h.

Definition at line 53 of file dji_drone.h.

Definition at line 84 of file dji_drone.h.

Definition at line 110 of file dji_drone.h.

Definition at line 57 of file dji_drone.h.

Definition at line 59 of file dji_drone.h.

Definition at line 58 of file dji_drone.h.

Definition at line 56 of file dji_drone.h.

dji_sdk::TransparentTransmissionData DJIDrone::mobile_data

Definition at line 102 of file dji_drone.h.

Definition at line 86 of file dji_drone.h.

Definition at line 95 of file dji_drone.h.

Callback Handler functions for Mobile data commands.

Definition at line 241 of file dji_drone.h.

nav_msgs::Odometry DJIDrone::odometry

Definition at line 105 of file dji_drone.h.

Definition at line 81 of file dji_drone.h.

dji_sdk::MissionStatusOther DJIDrone::other_mission_push_info

Definition at line 117 of file dji_drone.h.

dji_sdk::PowerStatus DJIDrone::power_status

Definition at line 101 of file dji_drone.h.

Definition at line 77 of file dji_drone.h.

dji_sdk::RCChannels DJIDrone::rc_channels

Definition at line 103 of file dji_drone.h.

Definition at line 78 of file dji_drone.h.

Definition at line 242 of file dji_drone.h.

Definition at line 44 of file dji_drone.h.

Definition at line 262 of file dji_drone.h.

Definition at line 260 of file dji_drone.h.

Definition at line 250 of file dji_drone.h.

Definition at line 263 of file dji_drone.h.

Definition at line 261 of file dji_drone.h.

Definition at line 251 of file dji_drone.h.

Definition at line 51 of file dji_drone.h.

Definition at line 243 of file dji_drone.h.

Definition at line 249 of file dji_drone.h.

dji_sdk::TimeStamp DJIDrone::time_stamp

Definition at line 106 of file dji_drone.h.

Definition at line 83 of file dji_drone.h.

dji_sdk::Velocity DJIDrone::velocity

Definition at line 104 of file dji_drone.h.

Definition at line 45 of file dji_drone.h.

Definition at line 79 of file dji_drone.h.

Definition at line 46 of file dji_drone.h.

Definition at line 49 of file dji_drone.h.

Definition at line 48 of file dji_drone.h.

Definition at line 258 of file dji_drone.h.

dji_sdk::MissionEventWpAction DJIDrone::waypoint_action_result

Definition at line 120 of file dji_drone.h.

dji_sdk::MissionStatusWaypoint DJIDrone::waypoint_mission_push_info

Definition at line 114 of file dji_drone.h.

Definition at line 34 of file dji_drone.h.

dji_sdk::MissionEventWpReach DJIDrone::waypoint_reached_result

Definition at line 121 of file dji_drone.h.

dji_sdk::MissionEventWpUpload DJIDrone::waypoint_upload_result

Definition at line 119 of file dji_drone.h.

Definition at line 255 of file dji_drone.h.


The documentation for this class was generated from the following file:


dji_sdk
Author(s): Botao Hu
autogenerated on Thu Jun 6 2019 17:55:30