strategy.h
Go to the documentation of this file.
00001 
00012 #ifndef UCL_DRONE_STRATEGY_H
00013 #define UCL_DRONE_STRATEGY_H
00014 
00015 // Header files
00016 #include <ros/ros.h>
00017 #include <signal.h>
00018 
00019 // #define USE_PROFILING
00020 #include <ucl_drone/profiling.h>
00021 
00022 // Messages
00023 #include <ucl_drone/DroneRole.h>
00024 #include <ucl_drone/DroneRoles.h>
00025 #include <ucl_drone/StrategyMsg.h>
00026 #include <ucl_drone/TargetDetected.h>
00027 
00028 class Strategy
00029 {
00030 private:
00031   std::string drone_name;
00032 
00033   ros::NodeHandle nh;
00034 
00035   ros::Publisher strategy_pub;
00036   ros::Subscriber target_sub;
00037   ros::Subscriber target_sub_from_master;
00038   ros::Subscriber target_sub_from_slave;
00039   ros::Subscriber multi_strategy_sub;
00040   ros::Subscriber navdata_sub;
00041   ros::Subscriber pose_from_slave_sub;
00042 
00043   std::string strategy_channel;
00044   std::string target_channel;
00045   std::string multi_strategy_channel;
00046   std::string target_channel_from_master;  
00047   std::string target_channel_from_slave;
00048   std::string navdata_channel;
00049   std::string pose_from_slave_channel;
00050 
00051   ucl_drone::TargetDetected lastTargetDetected;
00052   ucl_drone::TargetDetected lastTargetDetectedFromMaster;
00053   ucl_drone::TargetDetected lastTargetDetectedFromSlave;
00054 
00056 
00057   void targetDetectedCb(const ucl_drone::TargetDetected::ConstPtr targetDetectedPtr);
00058   void targetDetectedFromMasterCb(const ucl_drone::TargetDetected::ConstPtr targetDetectedPtr);
00059   void targetDetectedFromSlaveCb(const ucl_drone::TargetDetected::ConstPtr targetDetectedPtr);
00060   void multi_strategyCb(const ucl_drone::DroneRoles::ConstPtr drones_rolesPtr);
00061   void navdataCb(const ardrone_autonomy::Navdata::ConstPtr navdataPtr);
00062   void poseFromSlaveCb(const ucl_drone::Pose3D::ConstPtr posePtr);
00063 
00064   float xDetectedBySlave;
00065   float yDetectedBySlave;
00066   int i;
00067 
00068 public:
00070   Strategy();
00072   ~Strategy();
00073 
00074   ucl_drone::DroneRoles lastDronesrolesreceived;
00075 
00076   void init();
00077   void publish_strategy();
00078   void reset();
00079   void Takeoff();
00080   void Seek();
00081   void Goto();
00082   void Follow();
00083   void BackToBase();
00084   void Land();
00085   void SetXYChosen(double xchosen, double ychosen);
00086   int FindRole();
00087   float strategychosen;
00088   float oldstrategychosen;
00089   bool Drone1;
00090   bool Intheair;
00091   bool StrategyCbreceived;
00092   bool TargetDetectedFromMaster;
00093   bool TargetDetectedFromSlave;
00094   float batteryLeft;
00095   float oldbatteryLeft;
00096   bool backupCalled;
00097   float xchosen;
00098   float ychosen;
00099   ardrone_autonomy::Navdata lastNavdataReceived;
00100   ucl_drone::Pose3D lastPoseReceivedFromSlave;
00101 };
00102 
00103 #endif /*UCL_DRONE_STRATEGY_H */


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53