Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef RXTOOLS_ROSOUT_PANEL_H
00036 #define RXTOOLS_ROSOUT_PANEL_H
00037
00038 #include "rosout_generated.h"
00039 #include "rosout_filter.h"
00040 #include "rosgraph_msgs/Log.h"
00041
00042 #include <ros/ros.h>
00043 #include <ros/callback_queue.h>
00044
00045 #include <string>
00046 #include <vector>
00047 #include <map>
00048 #include <set>
00049
00050 #include "boost/thread/mutex.hpp"
00051 #include <boost/thread/thread.hpp>
00052
00053 class wxTimer;
00054 class wxTimerEvent;
00055 class wxAuiNotebook;
00056 class wxRichTextCtrl;
00057 class wxScrolledWindow;
00058 class wxSizer;
00059 class wxBitmapButton;
00060 class wxCheckBox;
00061 class wxWindow;
00062 class wxPanel;
00063 class wxEvent;
00064
00065 namespace rxtools
00066 {
00067
00068 class RosoutTextFilter;
00069 typedef boost::shared_ptr<RosoutTextFilter> RosoutTextFilterPtr;
00070
00071 class RosoutSeverityFilter;
00072 typedef boost::shared_ptr<RosoutSeverityFilter> RosoutSeverityFilterPtr;
00073
00074 typedef unsigned int uint32_t;
00075
00076 struct RosoutMessageSummary
00077 {
00078 RosoutMessageSummary()
00079 : debug(0)
00080 , info(0)
00081 , warn(0)
00082 , error(0)
00083 , fatal(0)
00084 {}
00085
00086 ~RosoutMessageSummary()
00087 {}
00088
00089 uint32_t debug;
00090 uint32_t info;
00091 uint32_t warn;
00092 uint32_t error;
00093 uint32_t fatal;
00094 };
00095
00100 class RosoutPanel : public RosoutPanelBase
00101 {
00102 public:
00103 struct FilterInfo
00104 {
00105 RosoutFilterPtr filter;
00106 wxWindow* control;
00107 wxSizer* sizer;
00108 wxCheckBox* enabled_cb;
00109 wxBitmapButton* delete_button;
00110 wxBitmapButton* up_button;
00111 wxBitmapButton* down_button;
00112 wxPanel* panel;
00113 };
00114
00115 public:
00120 RosoutPanel(wxWindow* parent, int id = wxID_ANY, wxPoint pos = wxDefaultPosition, wxSize size = wxDefaultSize, int style = wxTAB_TRAVERSAL);
00121 ~RosoutPanel();
00122
00129 void setEnabled(bool enabled);
00134 void setTopic(const std::string& topic);
00135
00139 void clear();
00140
00145 void setBufferSize(uint32_t size);
00146
00152 RosoutMessageSummary getMessageSummary(double duration) const;
00153
00159 rosgraph_msgs::LogConstPtr getMessageByIndex(uint32_t index) const;
00160
00161 RosoutTextFilterPtr createTextFilter();
00162 RosoutFrame* createNewFrame();
00163
00164 void clearFilters();
00165
00169 void refilter();
00170
00171 protected:
00175 virtual void onSetup(wxCommandEvent& event);
00179 virtual void onPause(wxCommandEvent& event);
00183 virtual void onClear(wxCommandEvent& event);
00184
00185 virtual void onNewWindow(wxCommandEvent& event);
00186 virtual void onLoggerLevels(wxCommandEvent& event);
00187 void onLoggerLevelsClose(wxCloseEvent& event);
00188
00192 void onProcessTimer(wxTimerEvent& evt);
00193
00194 void onAddFilterPressed(wxCommandEvent& event);
00195 void onFilterEnableChecked(wxCommandEvent& event);
00196 void onFilterDelete(wxCommandEvent& event);
00197 void onFilterMoveUp(wxCommandEvent& event);
00198 void onFilterMoveDown(wxCommandEvent& event);
00199
00201
00202 void onFilterChanged(const RosoutFilter*);
00203
00207 void subscribe();
00211 void unsubscribe();
00212
00216 void incomingMessage(const rosgraph_msgs::Log::ConstPtr& message);
00220 void processMessages();
00225 void processMessage(const rosgraph_msgs::Log::ConstPtr& message);
00231 void addMessageToTable(const rosgraph_msgs::Log::ConstPtr& message, uint32_t id);
00232
00238 bool filter(uint32_t id) const;
00239
00243 void popMessage();
00244
00245 void resizeFiltersPane();
00246 void updateFilterBackgrounds();
00247
00248 void addFilter(const RosoutFilterPtr& filter, wxWindow* control);
00249 void removeFilter(const RosoutFilterPtr& filter);
00250
00251 typedef std::map<uint32_t, rosgraph_msgs::Log::ConstPtr> M_IdToMessage;
00252
00253 void setMessages(const M_IdToMessage& messages);
00254
00255 void validateOrderedMessages();
00256
00257 bool enabled_;
00258 std::string topic_;
00259
00260 ros::NodeHandle nh_;
00261
00262 typedef std::vector<rosgraph_msgs::Log::ConstPtr> V_Log;
00263 V_Log message_queue_;
00264
00265 wxTimer* process_timer_;
00266
00267 uint32_t message_id_counter_;
00268
00269 M_IdToMessage messages_;
00270
00271 typedef std::vector<uint32_t> V_u32;
00272 V_u32 ordered_messages_;
00273
00274 uint32_t max_messages_;
00275 bool needs_refilter_;
00276 float refilter_timer_;
00277
00278 ros::CallbackQueue callback_queue_;
00279 ros::Subscriber sub_;
00280
00281 typedef std::vector<FilterInfo> V_FilterInfo;
00282 V_FilterInfo filters_;
00283
00284 RosoutSeverityFilterPtr severity_filter_;
00285
00286 wxBitmap delete_filter_bitmap_;
00287
00288 bool pause_;
00289
00290 LoggerLevelFrame* logger_level_frame_;
00291
00292 void checkForMaster();
00293
00294 bool connected_;
00295 boost::thread* check_master_thread_;
00296 bool shutdown_thread_;
00297
00298 const int RECONNECTED_TO_MASTER_EVENT_;
00299 const int DISCONNECTED_FROM_MASTER_EVENT_;
00300 void onMasterReconnected(wxEvent& event);
00301 void onMasterDisconnected(wxEvent& event);
00302 };
00303
00304 }
00305
00306 #endif // RXTOOLS_ROSOUT_PANEL_H