#include <statepublisher_rostopic.h>

Public Slots | |
| void | filterDialog (bool autoconfirm) |
| virtual void | setEnabled (bool enabled) override |
Public Member Functions | |
| virtual bool | enabled () const override |
| virtual const char * | name () const override |
| virtual void | play (double interval) override |
| void | setParentMenu (QMenu *menu, QAction *action) override |
| TopicPublisherROS () | |
| virtual void | updateState (double current_time) override |
| virtual | ~TopicPublisherROS () override |
Private Member Functions | |
| void | broadcastTF (double current_time) |
| void | publishAnyMsg (const rosbag::MessageInstance &msg_instance) |
| bool | toPublish (const std::string &topic_name) |
Private Member Functions inherited from StatePublisher | |
| virtual QWidget * | embeddedWidget () |
| virtual bool | isDebugPlugin () |
| void | setDataMap (const PlotDataMapRef *datamap) |
| virtual void | setEnabled (bool enabled) |
| virtual bool | xmlLoadState (const QDomElement &parent_element) |
| virtual bool | xmlSaveState (QDomDocument &doc, QDomElement &parent_element) const |
| QDomElement | xmlSaveState (QDomDocument &doc) const |
| virtual | ~StatePublisher () |
Private Attributes | |
| ros::Publisher | _clock_publisher |
| QAction * | _enable_self_action |
| bool | _enabled |
| ros::NodeHandlePtr | _node |
| int | _previous_play_index |
| bool | _publish_clock |
| std::map< std::string, ros::Publisher > | _publishers |
| QAction * | _select_topics_to_publish |
| std::unique_ptr< tf::TransformBroadcaster > | _tf_publisher |
| std::unordered_map< std::string, bool > | _topics_to_publish |
| double | previous_time |
Private Attributes inherited from StatePublisher | |
| QAction * | _action |
| const PlotDataMapRef * | _datamap |
| QMenu * | _menu |
Definition at line 14 of file statepublisher_rostopic.h.
| TopicPublisherROS::TopicPublisherROS | ( | ) |
Definition at line 22 of file statepublisher_rostopic.cpp.
|
overridevirtual |
Definition at line 32 of file statepublisher_rostopic.cpp.
|
private |
Definition at line 192 of file statepublisher_rostopic.cpp.
|
inlineoverridevirtual |
Implements StatePublisher.
Definition at line 28 of file statepublisher_rostopic.h.
|
slot |
Definition at line 84 of file statepublisher_rostopic.cpp.
|
inlineoverridevirtual |
Implements StatePublisher.
Definition at line 26 of file statepublisher_rostopic.h.
|
overridevirtual |
Implements StatePublisher.
Definition at line 422 of file statepublisher_rostopic.cpp.
|
private |
Definition at line 294 of file statepublisher_rostopic.cpp.
|
overridevirtualslot |
Definition at line 49 of file statepublisher_rostopic.cpp.
|
overridevirtual |
Reimplemented from StatePublisher.
Definition at line 37 of file statepublisher_rostopic.cpp.
|
private |
Definition at line 281 of file statepublisher_rostopic.cpp.
|
overridevirtual |
Implements StatePublisher.
Definition at line 348 of file statepublisher_rostopic.cpp.
|
private |
Definition at line 48 of file statepublisher_rostopic.h.
|
private |
Definition at line 50 of file statepublisher_rostopic.h.
|
private |
Definition at line 44 of file statepublisher_rostopic.h.
|
private |
Definition at line 45 of file statepublisher_rostopic.h.
|
private |
Definition at line 59 of file statepublisher_rostopic.h.
|
private |
Definition at line 46 of file statepublisher_rostopic.h.
|
private |
Definition at line 43 of file statepublisher_rostopic.h.
|
private |
Definition at line 51 of file statepublisher_rostopic.h.
|
private |
Definition at line 47 of file statepublisher_rostopic.h.
|
private |
Definition at line 53 of file statepublisher_rostopic.h.
|
private |
Definition at line 57 of file statepublisher_rostopic.h.