#include <connection_daemon.h>

Public Member Functions | |
| bool | CheckPassedTime () |
| ConnectionDaemon (float heartbeat) | |
| std::string | createPublishTopic () |
| void | LinkSubscriptionTopics (ros::NodeHandle *nh) |
| void | PublishConnection () |
| void | ROSConnectionStateCallback (const std_msgs::Bool::ConstPtr &msg) |
| void | UpdateConnection () |
Public Member Functions inherited from Daemon | |
| bool | CheckPassedTime () |
| bool | CheckRange (double lowerRange, double upperRange, double value, std::string msg_name) |
| bool | CheckTopic (std::string str1, std::string str2) |
| bool | CompareStrings (std::string str1, std::string str2) |
| std::string | CreateTimestamp () |
| void | createTopicStructurePrefix () |
| Daemon () | |
| Daemon (ros::NodeHandle *nh, std::string daemonName) | |
| vda5050_msgs::Header | GetHeader () |
| std::vector< std::string > | GetMsgList (std::map< std::string, std::string > topicList) |
| std::string | GetParameter (std::string param) |
| std::string | GetTopic (std::string hierarchical_topic) |
| std::map< std::string, std::string > | GetTopicPublisherList () |
| std::string | getTopicStructurePrefix () |
| std::map< std::string, std::string > | GetTopicSubscriberList () |
| void | InitHeaderInfo () |
| void | LinkErrorTopics (ros::NodeHandle *nh) |
| void | PublishState () |
| std::map< std::string, std::string > | ReadTopicParams (ros::NodeHandle *nh, std::string paramTopicName) |
| void | UpdateHeader () |
| void | UpdateState () |
Private Attributes | |
| vda5050_msgs::Connection | connectionMessage |
| ros::Publisher | connectionPublisher |
| ros::Subscriber | connectionSubscriber |
| ros::Time | lastUpdateTimestamp |
| ros::Duration | updateInterval |
Additional Inherited Members | |
Protected Attributes inherited from Daemon | |
| ros::Publisher | errorPublisher |
| std::map< std::string, ros::Publisher > | messagePublisher |
| ros::NodeHandle | nh |
| std::map< std::string, ros::Subscriber > | subscribers |
Daemon for processing VDA 5050 connection messages.
Definition at line 26 of file connection_daemon.h.
| ConnectionDaemon::ConnectionDaemon | ( | float | heartbeat | ) |
Constructor for stateDaemon objects.
| heartbeat | Time interval between connection updates. |
Definition at line 19 of file connection_daemon.cpp.
| bool ConnectionDaemon::CheckPassedTime | ( | ) |
Calculates the passed time between last update interval and now.
Definition at line 45 of file connection_daemon.cpp.
| std::string ConnectionDaemon::createPublishTopic | ( | ) |
Generates the name of the topic to publish. The topic name is built by adding the VDA-5050 global topic
Definition at line 38 of file connection_daemon.cpp.
| void ConnectionDaemon::LinkSubscriptionTopics | ( | ros::NodeHandle * | nh | ) |
Creates the subscribers for the required topics given from the config file.
| nh | Pointer to node handler. |
Definition at line 28 of file connection_daemon.cpp.
| void ConnectionDaemon::PublishConnection | ( | ) |
Fetches the header message and publishes the state message. Updates timestamp since last publishing.
Definition at line 51 of file connection_daemon.cpp.
| void ConnectionDaemon::ROSConnectionStateCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback for receiving information about the connection status of the ROS node.
| msg | Incoming message. |
Definition at line 71 of file connection_daemon.cpp.
| void ConnectionDaemon::UpdateConnection | ( | ) |
Checks all the logic within the state daemon. For example, it checks if 30 seconds have passed without update.
Definition at line 63 of file connection_daemon.cpp.
|
private |
Message containing connection information.
Definition at line 29 of file connection_daemon.h.
|
private |
Publisher for connection messages.
Definition at line 32 of file connection_daemon.h.
|
private |
Subscriber for connection messages.
Definition at line 35 of file connection_daemon.h.
|
private |
Last time the connection status was updated.
Definition at line 43 of file connection_daemon.h.
|
private |
Update interval to use for sending information about the connection status.
Definition at line 38 of file connection_daemon.h.