00001
00012 #ifndef __DJI_MISSION_NODE_H__
00013 #define __DJI_MISSION_NODE_H__
00014
00015 #include <ros/ros.h>
00016 #include <dji_sdk/dji_sdk.h>
00017
00018 #define C_PI (double) 3.141592653589793
00019
00020 extern DJI::onboardSDK::ROSAdapter *rosAdapter;
00021
00022 enum class MissionType
00023 {
00024 EMPTY,
00025 WAYPOINT,
00026 HOTPOINT,
00027 FOLLOWME
00028 };
00029
00030 class DJISDKMission
00031 {
00032 private:
00033 dji_sdk::MissionPushInfo mission_status;
00034 dji_sdk::MissionPushInfo mission_event;
00035
00036 dji_sdk::MissionWaypointTask waypoint_task;
00037 dji_sdk::MissionHotpointTask hotpoint_task;
00038 dji_sdk::MissionFollowmeTask followme_task;
00039
00040 public:
00041 DJISDKMission(ros::NodeHandle& nh);
00042 void mission_status_callback(uint8_t *buf, uint8_t len);
00043 void mission_event_callback(uint8_t *buf, uint8_t len);
00044 private:
00045
00046 ros::Publisher mission_status_publisher;
00047 ros::Publisher mission_event_publisher;
00048
00049
00050 ros::ServiceServer mission_start_service;
00051 ros::ServiceServer mission_pause_service;
00052 ros::ServiceServer mission_cancel_service;
00053
00054
00055 ros::ServiceServer mission_wp_upload_service;
00056 ros::ServiceServer mission_wp_download_service;
00057 ros::ServiceServer mission_wp_set_speed_service;
00058 ros::ServiceServer mission_wp_get_speed_service;
00059
00060
00061 ros::ServiceServer mission_hp_upload_service;
00062 ros::ServiceServer mission_hp_download_service;
00063 ros::ServiceServer mission_hp_set_speed_service;
00064 ros::ServiceServer mission_hp_set_radius_service;
00065 ros::ServiceServer mission_hp_reset_yaw_service;
00066
00067
00068 ros::ServiceServer mission_fm_upload_service;
00069 ros::ServiceServer mission_fm_set_target_service;
00070
00071 MissionType current_type = MissionType::EMPTY;
00072
00073 bool mission_start_callback(dji_sdk::MissionStart::Request& request, dji_sdk::MissionStart::Response& response);
00074 bool mission_pause_callback(dji_sdk::MissionPause::Request& request, dji_sdk::MissionPause::Response& response);
00075 bool mission_cancel_callback(dji_sdk::MissionCancel::Request& request, dji_sdk::MissionCancel::Response& response);
00076 bool mission_wp_upload_callback(dji_sdk::MissionWpUpload::Request& request, dji_sdk::MissionWpUpload::Response& response);
00077 bool mission_wp_download_callback(dji_sdk::MissionWpDownload::Request& request, dji_sdk::MissionWpDownload::Response& response);
00078 bool mission_wp_get_speed_callback(dji_sdk::MissionWpGetSpeed::Request& request, dji_sdk::MissionWpGetSpeed::Response& response);
00079 bool mission_wp_set_speed_callback(dji_sdk::MissionWpSetSpeed::Request& request, dji_sdk::MissionWpSetSpeed::Response& response);
00080 bool mission_hp_upload_callback(dji_sdk::MissionHpUpload::Request& request, dji_sdk::MissionHpUpload::Response& response);
00081 bool mission_hp_download_callback(dji_sdk::MissionHpDownload::Request& request, dji_sdk::MissionHpDownload::Response& response);
00082 bool mission_hp_set_speed_callback(dji_sdk::MissionHpSetSpeed::Request& request, dji_sdk::MissionHpSetSpeed::Response& response);
00083 bool mission_hp_set_radius_callback(dji_sdk::MissionHpSetRadius::Request& request, dji_sdk::MissionHpSetRadius::Response& response);
00084 bool mission_hp_reset_yaw_callback(dji_sdk::MissionHpResetYaw::Request& request, dji_sdk::MissionHpResetYaw::Response& response);
00085 bool mission_fm_upload_callback(dji_sdk::MissionFmUpload::Request& request, dji_sdk::MissionFmUpload::Response& response);
00086 bool mission_fm_set_target_callback(dji_sdk::MissionFmSetTarget::Request& request, dji_sdk::MissionFmSetTarget::Response& response);
00087
00088
00089 void init_missions(ros::NodeHandle& nh)
00090 {
00091 mission_status_publisher = nh.advertise<dji_sdk::MissionPushInfo>("dji_sdk/mission_status", 10);
00092 mission_event_publisher = nh.advertise<dji_sdk::MissionPushInfo>("dji_sdk/mission_event", 10);
00093
00094 mission_start_service = nh.advertiseService("dji_sdk/mission_start", &DJISDKMission::mission_start_callback ,this);
00095 mission_pause_service = nh.advertiseService("dji_sdk/mission_pause", &DJISDKMission::mission_pause_callback ,this);
00096 mission_cancel_service = nh.advertiseService("dji_sdk/mission_cancel", &DJISDKMission::mission_cancel_callback ,this);
00097 mission_wp_upload_service = nh.advertiseService("dji_sdk/mission_waypoint_upload", &DJISDKMission::mission_wp_upload_callback,this);
00098 mission_wp_download_service = nh.advertiseService("dji_sdk/mission_waypoint_download", &DJISDKMission::mission_wp_download_callback,this);
00099 mission_wp_set_speed_service = nh.advertiseService("dji_sdk/mission_waypoint_set_speed", &DJISDKMission::mission_wp_set_speed_callback ,this);
00100 mission_wp_get_speed_service = nh.advertiseService("dji_sdk/mission_waypoint_get_speed", &DJISDKMission::mission_wp_get_speed_callback ,this);
00101 mission_hp_upload_service = nh.advertiseService("dji_sdk/mission_hotpoint_upload", &DJISDKMission::mission_hp_upload_callback ,this);
00102 mission_hp_download_service = nh.advertiseService("dji_sdk/mission_hotpoint_download", &DJISDKMission::mission_hp_download_callback,this);
00103 mission_hp_set_speed_service = nh.advertiseService("dji_sdk/mission_hotpoint_set_speed", &DJISDKMission::mission_hp_set_speed_callback ,this);
00104 mission_hp_set_radius_service = nh.advertiseService("dji_sdk/mission_hotpoint_set_radius", &DJISDKMission::mission_hp_set_radius_callback ,this);
00105 mission_hp_reset_yaw_service = nh.advertiseService("dji_sdk/mission_hotpoint_reset_yaw", &DJISDKMission::mission_hp_reset_yaw_callback ,this);
00106 mission_fm_upload_service = nh.advertiseService("dji_sdk/mission_followme_upload", &DJISDKMission::mission_fm_upload_callback ,this);
00107 mission_fm_set_target_service = nh.advertiseService("dji_sdk/mission_followme_set_target", &DJISDKMission::mission_fm_set_target_callback ,this);
00108
00109 }
00110 };
00111
00112 #endif