The TopicDisplay class is an embeddable panel encapsulating a treeview that displays list of topics advertised on the master. It is also possible to filter this list to only show topics of a specific message type. More...
#include <topic_display.h>

Classes | |
| struct | TopicInfo |
| Structure used to store information about a topic we've received. More... | |
Public Member Functions | |
| void | getSelectedTopics (V_string &topics) |
| Get the topics that have been selected in the list. If multiple selection is disallowed, this will return a 0 or 1 length vector. | |
| void | setMultiselectAllowed (bool allowed) |
| Set whether multiple selection of topics is allowed by the treeview. | |
| TopicDisplay (wxWindow *parent, const std::string &message_type="", bool auto_refresh=true, const wxSize &size=wxSize(500, 300)) | |
| Constructor. | |
| virtual | ~TopicDisplay () |
Private Types | |
| typedef std::map< std::string, TopicInfo > | M_TopicInfo |
Private Member Functions | |
| virtual void | checkIsTopic (wxTreeEvent &event) |
| virtual void | onItemActivated (wxTreeEvent &event) |
| virtual void | refreshTopics () |
| virtual void | tick (wxTimerEvent &event) |
Private Attributes | |
| std::string | message_type_ |
| Message type to filter by (blank == show all). | |
| ros::NodeHandle | nh_ |
| wxTreeItemId | root_id_ |
| Tree item id for the root of the tree. | |
| wxTimer * | timer_ |
| Timer controlling our refresh rate. | |
| M_TopicInfo | topic_cache_ |
| Cache of topic info, used when refreshing. | |
The TopicDisplay class is an embeddable panel encapsulating a treeview that displays list of topics advertised on the master. It is also possible to filter this list to only show topics of a specific message type.
Definition at line 53 of file topic_display.h.
typedef std::map<std::string, TopicInfo> rxtools::TopicDisplay::M_TopicInfo [private] |
Definition at line 86 of file topic_display.h.
| rxtools::TopicDisplay::TopicDisplay | ( | wxWindow * | parent, | |
| const std::string & | message_type = "", |
|||
| bool | auto_refresh = true, |
|||
| const wxSize & | size = wxSize(500, 300) | |||
| ) |
Constructor.
| parent | The parent window for this panel | |
| node | The ROS node | |
| message_type | The message type to filter by, or empty string to show all types. If this is set, the panel will only display topics of this type | |
| size | The size of the panel |
Definition at line 44 of file topic_display.cpp.
| rxtools::TopicDisplay::~TopicDisplay | ( | ) | [virtual] |
Definition at line 62 of file topic_display.cpp.
| void rxtools::TopicDisplay::checkIsTopic | ( | wxTreeEvent & | event | ) | [private, virtual] |
Reimplemented from rxtools::GenTopicDisplay.
Definition at line 67 of file topic_display.cpp.
| void rxtools::TopicDisplay::getSelectedTopics | ( | V_string & | topics | ) |
Get the topics that have been selected in the list. If multiple selection is disallowed, this will return a 0 or 1 length vector.
Definition at line 219 of file topic_display.cpp.
| void rxtools::TopicDisplay::onItemActivated | ( | wxTreeEvent & | event | ) | [private, virtual] |
Reimplemented from rxtools::GenTopicDisplay.
Definition at line 75 of file topic_display.cpp.
| void rxtools::TopicDisplay::refreshTopics | ( | ) | [private, virtual] |
Definition at line 87 of file topic_display.cpp.
| void rxtools::TopicDisplay::setMultiselectAllowed | ( | bool | allowed | ) |
Set whether multiple selection of topics is allowed by the treeview.
Definition at line 236 of file topic_display.cpp.
| void rxtools::TopicDisplay::tick | ( | wxTimerEvent & | event | ) | [private, virtual] |
Definition at line 214 of file topic_display.cpp.
std::string rxtools::TopicDisplay::message_type_ [private] |
Message type to filter by (blank == show all).
Definition at line 94 of file topic_display.h.
ros::NodeHandle rxtools::TopicDisplay::nh_ [private] |
Definition at line 89 of file topic_display.h.
wxTreeItemId rxtools::TopicDisplay::root_id_ [private] |
Tree item id for the root of the tree.
Definition at line 92 of file topic_display.h.
wxTimer* rxtools::TopicDisplay::timer_ [private] |
Timer controlling our refresh rate.
Definition at line 88 of file topic_display.h.
Cache of topic info, used when refreshing.
Definition at line 90 of file topic_display.h.