Go to the documentation of this file.00001 #pragma once
00002
00021 #ifndef __CONTROLNODE_H
00022 #define __CONTROLNODE_H
00023
00024 #include "ros/ros.h"
00025 #include "geometry_msgs/Twist.h"
00026 #include "tum_ardrone/filter_state.h"
00027 #include "std_msgs/String.h"
00028 #include <dynamic_reconfigure/server.h>
00029 #include "tum_ardrone/AutopilotParamsConfig.h"
00030 #include "DroneController.h"
00031 #include "std_msgs/Empty.h"
00032 #include "std_srvs/Empty.h"
00033
00034 #include "tum_ardrone/SetReference.h"
00035 #include "tum_ardrone/SetMaxControl.h"
00036 #include "tum_ardrone/SetInitialReachDistance.h"
00037 #include "tum_ardrone/SetStayWithinDistance.h"
00038 #include "tum_ardrone/SetStayTime.h"
00039 #include "std_srvs/Empty.h"
00040
00041 class DroneKalmanFilter;
00042 class MapView;
00043 class PTAMWrapper;
00044 class KIProcedure;
00045
00046
00047 struct ControlNode
00048 {
00049 private:
00050 ros::Subscriber dronepose_sub;
00051 ros::Publisher vel_pub;
00052 ros::Subscriber tum_ardrone_sub;
00053 ros::Publisher tum_ardrone_pub;
00054 ros::Publisher takeoff_pub;
00055 ros::Publisher land_pub;
00056 ros::Publisher toggleState_pub;
00057
00058 ros::NodeHandle nh_;
00059 static pthread_mutex_t tum_ardrone_CS;
00060
00061
00062 int minPublishFreq;
00063 std::string control_channel;
00064 std::string dronepose_channel;
00065 std::string command_channel;
00066 std::string packagePath;
00067 std::string land_channel;
00068 std::string takeoff_channel;
00069 std::string toggleState_channel;
00070
00071
00072 ros::ServiceServer setReference_;
00073 ros::ServiceServer setMaxControl_;
00074 ros::ServiceServer setInitialReachDistance_;
00075 ros::ServiceServer setStayWithinDistance_;
00076 ros::ServiceServer setStayTime_;
00077 ros::ServiceServer startControl_;
00078 ros::ServiceServer stopControl_;
00079 ros::ServiceServer clearCommands_;
00080 ros::ServiceServer hover_;
00081 ros::ServiceServer lockScaleFP_;
00082
00083 bool setReference(tum_ardrone::SetReference::Request&, tum_ardrone::SetReference::Response&);
00084 bool setMaxControl(tum_ardrone::SetMaxControl::Request&, tum_ardrone::SetMaxControl::Response&);
00085 bool setInitialReachDistance(tum_ardrone::SetInitialReachDistance::Request&, tum_ardrone::SetInitialReachDistance::Response&);
00086 bool setStayWithinDistance(tum_ardrone::SetStayWithinDistance::Request&, tum_ardrone::SetStayWithinDistance::Response&);
00087 bool setStayTime(tum_ardrone::SetStayTime::Request&, tum_ardrone::SetStayTime::Response&);
00088 bool start(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00089 bool stop(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00090 bool clear(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00091 bool hover(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00092 bool lockScaleFP(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00093
00094
00095 std::deque<std::string> commandQueue;
00096 static pthread_mutex_t commandQueue_CS;
00097
00098
00099
00100 KIProcedure* currentKI;
00101
00102
00103 DronePosition parameter_referenceZero;
00104 double parameter_StayTime;
00105 double parameter_MaxControl;
00106 double parameter_InitialReachDist;
00107 double parameter_StayWithinDist;
00108
00109
00110 void startControl();
00111 void stopControl();
00112 void clearCommands();
00113 void updateControl(const tum_ardrone::filter_stateConstPtr statePtr);
00114
00115 void popNextCommand(const tum_ardrone::filter_stateConstPtr statePtr);
00116 void reSendInfo();
00117 char buf[500];
00118 ControlCommand lastSentControl;
00119 public:
00120 ControlNode();
00121 ~ControlNode();
00122
00123
00124
00125 void droneposeCb(const tum_ardrone::filter_stateConstPtr statePtr);
00126 void comCb(const std_msgs::StringConstPtr str);
00127 void dynConfCb(tum_ardrone::AutopilotParamsConfig &config, uint32_t level);
00128
00129
00130 void Loop();
00131
00132
00133
00134 void publishCommand(std::string c);
00135
00136
00137 void sendControlToDrone(ControlCommand cmd);
00138 void sendLand();
00139 void sendTakeoff();
00140 void sendToggleState();
00141
00142
00143 DroneController controller;
00144 ControlCommand hoverCommand;
00145
00146
00147 std::ofstream* logfileControl;
00148 static pthread_mutex_t logControl_CS;
00149 void toogleLogging();
00150
00151
00152 long lastControlSentMS;
00153 bool isControlling;
00154 };
00155 #endif