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
00052 class wxTimer;
00053 class wxTimerEvent;
00054 class wxAuiNotebook;
00055 class wxRichTextCtrl;
00056 class wxScrolledWindow;
00057 class wxSizer;
00058 class wxBitmapButton;
00059 class wxCheckBox;
00060 class wxWindow;
00061 class wxPanel;
00062
00063 namespace rxtools
00064 {
00065
00066 class RosoutTextFilter;
00067 typedef boost::shared_ptr<RosoutTextFilter> RosoutTextFilterPtr;
00068
00069 class RosoutSeverityFilter;
00070 typedef boost::shared_ptr<RosoutSeverityFilter> RosoutSeverityFilterPtr;
00071
00072 typedef unsigned int uint32_t;
00073
00074 struct RosoutMessageSummary
00075 {
00076 RosoutMessageSummary()
00077 : debug(0)
00078 , info(0)
00079 , warn(0)
00080 , error(0)
00081 , fatal(0)
00082 {}
00083
00084 ~RosoutMessageSummary()
00085 {}
00086
00087 uint32_t debug;
00088 uint32_t info;
00089 uint32_t warn;
00090 uint32_t error;
00091 uint32_t fatal;
00092 };
00093
00098 class RosoutPanel : public RosoutPanelBase
00099 {
00100 public:
00101 struct FilterInfo
00102 {
00103 RosoutFilterPtr filter;
00104 wxWindow* control;
00105 wxSizer* sizer;
00106 wxCheckBox* enabled_cb;
00107 wxBitmapButton* delete_button;
00108 wxBitmapButton* up_button;
00109 wxBitmapButton* down_button;
00110 wxPanel* panel;
00111 };
00112
00113 public:
00118 RosoutPanel(wxWindow* parent, int id = wxID_ANY, wxPoint pos = wxDefaultPosition, wxSize size = wxDefaultSize, int style = wxTAB_TRAVERSAL);
00119 ~RosoutPanel();
00120
00127 void setEnabled(bool enabled);
00132 void setTopic(const std::string& topic);
00133
00137 void clear();
00138
00143 void setBufferSize(uint32_t size);
00144
00150 RosoutMessageSummary getMessageSummary(double duration) const;
00151
00157 rosgraph_msgs::LogConstPtr getMessageByIndex(uint32_t index) const;
00158
00159 RosoutTextFilterPtr createTextFilter();
00160 RosoutFrame* createNewFrame();
00161
00162 void clearFilters();
00163
00167 void refilter();
00168
00169 protected:
00173 virtual void onSetup(wxCommandEvent& event);
00177 virtual void onPause(wxCommandEvent& event);
00181 virtual void onClear(wxCommandEvent& event);
00182
00183 virtual void onNewWindow(wxCommandEvent& event);
00184 virtual void onLoggerLevels(wxCommandEvent& event);
00185 void onLoggerLevelsClose(wxCloseEvent& event);
00186
00190 void onProcessTimer(wxTimerEvent& evt);
00191
00192 void onAddFilterPressed(wxCommandEvent& event);
00193 void onFilterEnableChecked(wxCommandEvent& event);
00194 void onFilterDelete(wxCommandEvent& event);
00195 void onFilterMoveUp(wxCommandEvent& event);
00196 void onFilterMoveDown(wxCommandEvent& event);
00197
00199
00200 void onFilterChanged(const RosoutFilter*);
00201
00205 void subscribe();
00209 void unsubscribe();
00210
00214 void incomingMessage(const rosgraph_msgs::Log::ConstPtr& message);
00218 void processMessages();
00223 void processMessage(const rosgraph_msgs::Log::ConstPtr& message);
00229 void addMessageToTable(const rosgraph_msgs::Log::ConstPtr& message, uint32_t id);
00230
00236 bool filter(uint32_t id) const;
00237
00241 void popMessage();
00242
00243 void resizeFiltersPane();
00244 void updateFilterBackgrounds();
00245
00246 void addFilter(const RosoutFilterPtr& filter, wxWindow* control);
00247 void removeFilter(const RosoutFilterPtr& filter);
00248
00249 typedef std::map<uint32_t, rosgraph_msgs::Log::ConstPtr> M_IdToMessage;
00250
00251 void setMessages(const M_IdToMessage& messages);
00252
00253 void validateOrderedMessages();
00254
00255 bool enabled_;
00256 std::string topic_;
00257
00258 ros::NodeHandle nh_;
00259
00260 typedef std::vector<rosgraph_msgs::Log::ConstPtr> V_Log;
00261 V_Log message_queue_;
00262
00263 wxTimer* process_timer_;
00264
00265 uint32_t message_id_counter_;
00266
00267 M_IdToMessage messages_;
00268
00269 typedef std::vector<uint32_t> V_u32;
00270 V_u32 ordered_messages_;
00271
00272 uint32_t max_messages_;
00273 bool needs_refilter_;
00274 float refilter_timer_;
00275
00276 ros::CallbackQueue callback_queue_;
00277 ros::Subscriber sub_;
00278
00279 typedef std::vector<FilterInfo> V_FilterInfo;
00280 V_FilterInfo filters_;
00281
00282 RosoutSeverityFilterPtr severity_filter_;
00283
00284 wxBitmap delete_filter_bitmap_;
00285
00286 bool pause_;
00287
00288 LoggerLevelFrame* logger_level_frame_;
00289 };
00290
00291 }
00292
00293 #endif // RXTOOLS_ROSOUT_PANEL_H