EstimationNode.h
Go to the documentation of this file.
00001 #pragma once
00002 
00021 #ifndef __ESTIMATIONNODE_H
00022 #define __ESTIMATIONNODE_H
00023  
00024 
00025 #include "ros/ros.h"
00026 #include "geometry_msgs/Twist.h"
00027 #include "sensor_msgs/Image.h"
00028 #include "tf/tfMessage.h"
00029 #include "tf/transform_listener.h"
00030 #include "tf/transform_broadcaster.h"
00031 #include "std_msgs/Empty.h"
00032 #include "std_srvs/Empty.h"
00033 #include "ardrone_autonomy/Navdata.h"
00034 #include "tum_ardrone/filter_state.h"
00035 #include "std_msgs/String.h"
00036 #include <dynamic_reconfigure/server.h>
00037 #include "tum_ardrone/StateestimationParamsConfig.h"
00038 #include "TooN/se3.h"
00039 
00040 
00041 class DroneKalmanFilter;
00042 class MapView;
00043 class PTAMWrapper;
00044 
00045 struct EstimationNode
00046 {
00047 private:
00048         // comm with drone
00049         ros::Subscriber navdata_sub; // drone navdata
00050         ros::Subscriber vel_sub; // to co-read contro commands sent from other thread
00051         ros::Subscriber vid_sub;
00052         ros::Time lastNavStamp;
00053 
00054 
00055         // comm with ptam
00056         //ros::Subscriber slam_info_sub; // ptam info (tracking quality) etc.
00057         //tf::TransformListener tf_sub;
00058         ros::Subscriber tum_ardrone_sub;
00059         ros::Publisher tum_ardrone_pub;
00060         static pthread_mutex_t tum_ardrone_CS;
00061 
00062         // output
00063         ros::Publisher dronepose_pub;
00064 
00065         ros::NodeHandle nh_;
00066 
00067         tf::TransformBroadcaster tf_broadcaster;
00068 
00069         // parameters
00070         // every [publishFreq]ms, the node publishes the drones predicted position [predTime]ms into the future.
00071         // this pose can then be used to steer the drone. obviously, the larger [predTime], the worse the estimate.
00072         // this pose is published on /tf, and simultaneously further info is published on /ardrone/predictedPose
00073         ros::Duration predTime;
00074         int publishFreq;
00075 
00076         std::string navdata_channel;
00077         std::string control_channel;
00078         std::string output_channel;
00079         std::string video_channel;
00080         std::string command_channel;
00081 
00082 
00083 
00084         // for navdata time-smoothing
00085         long lastDroneTS;
00086         long lastRosTS;
00087         long droneRosTSOffset;
00088 
00089 
00090         // save last navinfo received for forwarding...
00091         ardrone_autonomy::Navdata lastNavdataReceived;
00092 
00093 public:
00094         // filter
00095         DroneKalmanFilter* filter;
00096         PTAMWrapper* ptamWrapper;
00097         MapView* mapView;
00098         std::string packagePath;
00099 
00100         EstimationNode();
00101         ~EstimationNode();
00102 
00103 
00104         // ROS message callbacks
00105         void navdataCb(const ardrone_autonomy::NavdataConstPtr navdataPtr);
00106         void velCb(const geometry_msgs::TwistConstPtr velPtr);
00107         void vidCb(const sensor_msgs::ImageConstPtr img);
00108         void comCb(const std_msgs::StringConstPtr str);
00109         void dynConfCb(tum_ardrone::StateestimationParamsConfig &config, uint32_t level);
00110 
00111         // main pose-estimation loop
00112         void Loop();
00113 
00114         // writes a string message to "/tum_ardrone/com".
00115         // is thread-safe (can be called by any thread, but may block till other calling thread finishes)
00116         void publishCommand(std::string c);
00117         void reSendInfo();
00118 
00119         void publishTf(TooN::SE3<>, ros::Time stamp, int seq, std::string system);
00120 
00121         // logging stuff
00122         // logging stuff
00123         std::ofstream* logfileIMU;
00124         std::ofstream* logfilePTAM;
00125         std::ofstream* logfileFilter;
00126         std::ofstream* logfilePTAMRaw;
00127         static pthread_mutex_t logIMU_CS;
00128         static pthread_mutex_t logPTAM_CS;
00129         static pthread_mutex_t logFilter_CS;
00130         static pthread_mutex_t logPTAMRaw_CS;
00131         long currentLogID;
00132         long startedLogClock;
00133 
00134         void toogleLogging();   // switches logging on or off.
00135         std::string calibFile;
00136         int arDroneVersion;
00137 
00138 
00139 };
00140 #endif /* __ESTIMATIONNODE_H */


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