#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 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 |
Definition at line 14 of file statepublisher_rostopic.h.
Definition at line 22 of file statepublisher_rostopic.cpp.
| TopicPublisherROS::~TopicPublisherROS | ( | ) | [override, virtual] |
Definition at line 32 of file statepublisher_rostopic.cpp.
| void TopicPublisherROS::broadcastTF | ( | double | current_time | ) | [private] |
Definition at line 192 of file statepublisher_rostopic.cpp.
| virtual bool TopicPublisherROS::enabled | ( | ) | const [inline, override, virtual] |
Implements StatePublisher.
Definition at line 28 of file statepublisher_rostopic.h.
| void TopicPublisherROS::filterDialog | ( | bool | autoconfirm | ) | [slot] |
Definition at line 84 of file statepublisher_rostopic.cpp.
| virtual const char* TopicPublisherROS::name | ( | ) | const [inline, override, virtual] |
Implements StatePublisher.
Definition at line 26 of file statepublisher_rostopic.h.
| void TopicPublisherROS::play | ( | double | interval | ) | [override, virtual] |
Implements StatePublisher.
Definition at line 422 of file statepublisher_rostopic.cpp.
| void TopicPublisherROS::publishAnyMsg | ( | const rosbag::MessageInstance & | msg_instance | ) | [private] |
Definition at line 294 of file statepublisher_rostopic.cpp.
| void TopicPublisherROS::setEnabled | ( | bool | enabled | ) | [override, virtual, slot] |
Reimplemented from StatePublisher.
Definition at line 49 of file statepublisher_rostopic.cpp.
| void TopicPublisherROS::setParentMenu | ( | QMenu * | menu, |
| QAction * | action | ||
| ) | [override, virtual] |
Reimplemented from StatePublisher.
Definition at line 37 of file statepublisher_rostopic.cpp.
| bool TopicPublisherROS::toPublish | ( | const std::string & | topic_name | ) | [private] |
Definition at line 281 of file statepublisher_rostopic.cpp.
| void TopicPublisherROS::updateState | ( | double | current_time | ) | [override, virtual] |
Implements StatePublisher.
Definition at line 348 of file statepublisher_rostopic.cpp.
Definition at line 48 of file statepublisher_rostopic.h.
QAction* TopicPublisherROS::_enable_self_action [private] |
Definition at line 50 of file statepublisher_rostopic.h.
bool TopicPublisherROS::_enabled [private] |
Definition at line 44 of file statepublisher_rostopic.h.
ros::NodeHandlePtr TopicPublisherROS::_node [private] |
Definition at line 45 of file statepublisher_rostopic.h.
int TopicPublisherROS::_previous_play_index [private] |
Definition at line 59 of file statepublisher_rostopic.h.
bool TopicPublisherROS::_publish_clock [private] |
Definition at line 46 of file statepublisher_rostopic.h.
std::map<std::string, ros::Publisher> TopicPublisherROS::_publishers [private] |
Definition at line 43 of file statepublisher_rostopic.h.
QAction* TopicPublisherROS::_select_topics_to_publish [private] |
Definition at line 51 of file statepublisher_rostopic.h.
std::unique_ptr<tf::TransformBroadcaster> TopicPublisherROS::_tf_publisher [private] |
Definition at line 47 of file statepublisher_rostopic.h.
std::unordered_map<std::string,bool> TopicPublisherROS::_topics_to_publish [private] |
Definition at line 53 of file statepublisher_rostopic.h.
double TopicPublisherROS::previous_time [private] |
Definition at line 57 of file statepublisher_rostopic.h.