RosThread.h
Go to the documentation of this file.
00001 #pragma once
00002 
00021 #ifndef __ROSTHREAD_H
00022 #define __ROSTHREAD_H
00023  
00024  
00025 
00026 #include "cvd/thread.h"
00027 #include "tum_ardrone/filter_state.h"
00028 #include "std_msgs/String.h"
00029 #include "geometry_msgs/Twist.h"
00030 #include "ardrone_autonomy/Navdata.h"
00031 #include "ros/ros.h"
00032 #include "sensor_msgs/Joy.h"
00033 #include "std_srvs/Empty.h"
00034 #include "std_msgs/Empty.h"
00035 
00036 class tum_ardrone_gui;
00037 
00038 struct ControlCommand
00039 {
00040         inline ControlCommand() {roll = pitch = yaw = gaz = 0;}
00041         inline ControlCommand(double roll, double pitch, double yaw, double gaz)
00042         {
00043                 this->roll = roll;
00044                 this->pitch = pitch;
00045                 this->yaw = yaw;
00046                 this->gaz = gaz;
00047         }
00048         double yaw, roll, pitch, gaz;
00049 };
00050 
00051 class RosThread : private CVD::Thread
00052 {
00053 private:
00054         // the associated thread's run function.
00055         void run();
00056 
00057         // keep Running
00058         bool keepRunning;
00059 
00060         // ros stuff
00061         ros::Subscriber dronepose_sub;
00062         ros::Publisher vel_pub;
00063         ros::Subscriber vel_sub;
00064         ros::Subscriber tum_ardrone_sub;
00065         ros::Publisher tum_ardrone_pub;
00066         ros::Subscriber navdata_sub;
00067         ros::Subscriber joy_sub;
00068         ros::Publisher takeoff_pub;
00069         ros::Publisher land_pub;
00070         ros::Publisher toggleState_pub;
00071         ros::ServiceClient toggleCam_srv;
00072         std_srvs::Empty toggleCam_srv_srvs;
00073         ros::ServiceClient flattrim_srv;
00074         std_srvs::Empty flattrim_srv_srvs;
00075         ros::Subscriber takeoff_sub;
00076         ros::Subscriber land_sub;
00077         ros::Subscriber toggleState_sub;
00078 
00079 
00080         ros::NodeHandle nh_;
00081 
00082         // counters for Hz
00083         unsigned int dronePoseCount;
00084         unsigned int velCount;
00085         unsigned int navdataCount;
00086         unsigned int joyCount;
00087         unsigned int velCount100ms;
00088 
00089         static pthread_mutex_t send_CS;
00090 public:
00091         RosThread(void);
00092         ~RosThread(void);
00093 
00094         // start and stop system and respective thread.
00095         // to be called externally
00096         void startSystem();
00097         void stopSystem();
00098 
00099         tum_ardrone_gui* gui;
00100 
00101 
00102         // callbacks
00103         void droneposeCb(const tum_ardrone::filter_stateConstPtr statePtr);
00104         void comCb(const std_msgs::StringConstPtr str);
00105         void velCb(const geometry_msgs::TwistConstPtr vel);
00106         void navdataCb(const ardrone_autonomy::NavdataConstPtr navdataPtr);
00107         void joyCb(const sensor_msgs::JoyConstPtr joy_msg);
00108         void landCb(std_msgs::EmptyConstPtr);
00109         void toggleStateCb(std_msgs::EmptyConstPtr);
00110         void takeoffCb(std_msgs::EmptyConstPtr);
00111         ControlCommand lastJoyControlSent;
00112         bool lastL1Pressed;
00113         bool lastR1Pressed;
00114 
00115 
00116         // send command functions. can be called from any thread & are thread-safe.
00117         // writes a string message to "/tum_ardrone/com".
00118         // is thread-safe (can be called by any thread, but may block till other calling thread finishes)
00119         void publishCommand(std::string c);
00120         void sendControlToDrone(ControlCommand cmd);
00121         void sendLand();
00122         void sendTakeoff();
00123         void sendToggleState();
00124         void sendToggleCam();
00125         void sendFlattrim();
00126 };
00127 
00128 #endif /* __ROSTHREAD_H */


tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:27:23