#include <visualization_daemon.h>

Public Member Functions | |
| void | AGVPositionCallback (const vda5050_msgs::AGVPosition::ConstPtr &msg) |
| void | AGVPositionDeviationRangeCallback (const std_msgs::Float64::ConstPtr &msg) |
| void | AGVPositionInitializedCallback (const std_msgs::Bool::ConstPtr &msg) |
| void | AGVPositionLocalizationScoreCallback (const std_msgs::Float64::ConstPtr &msg) |
| void | AGVPositionMapDescriptionCallback (const std_msgs::String::ConstPtr &msg) |
| void | AGVPositionMapIdCallback (const std_msgs::String::ConstPtr &msg) |
| double | CalculateAgvOrientation (const nav_msgs::Odometry::ConstPtr &msg) |
| bool | CheckPassedTime () |
| void | LinkPublishTopics (ros::NodeHandle *nh) |
| void | LinkSubscriptionTopics (ros::NodeHandle *nh) |
| void | PublishVisualization () |
| void | ROSAGVPositionCallback (const nav_msgs::Odometry::ConstPtr &msg) |
| void | ROSVelocityCallback (const nav_msgs::Odometry::ConstPtr &msg) |
| void | UpdateVisualization () |
| VisDaemon () | |
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 | |
| ros::Time | lastUpdateTimestamp |
| ros::Publisher | pub |
| ros::Duration | updateInterval |
| vda5050_msgs::Visualization | visMessage |
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 visualziation messages. This daemon gathers relevant information from different sources of the robot's communication system, i. e. different ROS topics. The collected information is then compiled into the form which the VDA 5050 expects. State messages are repeatedly sent to the MQTT bridge so that they can be transmitted to the fleet control system with the desired frequency.
Definition at line 46 of file visualization_daemon.h.
| VisDaemon::VisDaemon | ( | ) |
Standard Constructor.
Definition at line 18 of file visualization_daemon.cpp.
| void VisDaemon::AGVPositionCallback | ( | const vda5050_msgs::AGVPosition::ConstPtr & | msg | ) |
Callback function for incoming position messages.
| msg | Incoming message. |
Definition at line 133 of file visualization_daemon.cpp.
| void VisDaemon::AGVPositionDeviationRangeCallback | ( | const std_msgs::Float64::ConstPtr & | msg | ) |
Callback function for incoming information about the deviation range of the AGV's position.
| msg | Incoming message. |
Definition at line 155 of file visualization_daemon.cpp.
| void VisDaemon::AGVPositionInitializedCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback function for the incoming notification when the AGV position was initialized.
| msg | Incoming message. |
Definition at line 144 of file visualization_daemon.cpp.
| void VisDaemon::AGVPositionLocalizationScoreCallback | ( | const std_msgs::Float64::ConstPtr & | msg | ) |
Callback function for incoming information about the localization score of the AGV.
| msg | Incoming message. |
Definition at line 148 of file visualization_daemon.cpp.
| void VisDaemon::AGVPositionMapDescriptionCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function for incoming map description strings of the AGV's position.
| msg | Incoming message. |
Definition at line 163 of file visualization_daemon.cpp.
| void VisDaemon::AGVPositionMapIdCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function for incoming MapIDs of the AGV's position.
| msg | Incoming message. |
Definition at line 159 of file visualization_daemon.cpp.
| double VisDaemon::CalculateAgvOrientation | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Calculate the AGV's rotation from odometry data.
| msg | Odometry message that should be used for calculation. |
Definition at line 91 of file visualization_daemon.cpp.
| bool VisDaemon::CheckPassedTime | ( | ) |
Calculates the passed time between last update interval and now.
Definition at line 27 of file visualization_daemon.cpp.
| void VisDaemon::LinkPublishTopics | ( | ros::NodeHandle * | nh | ) |
Creates the publisher for the required topics. The list of topics is extracted from the config file.
| nh | Pointer to the node handler. |
Definition at line 50 of file visualization_daemon.cpp.
| void VisDaemon::LinkSubscriptionTopics | ( | ros::NodeHandle * | nh | ) |
Creates the subscribers for the required topics. The list of topics is extracted from the config file.
| nh | Pointer to node handler. |
Definition at line 67 of file visualization_daemon.cpp.
| void VisDaemon::PublishVisualization | ( | ) |
Fetches the header message and publishes the state message. Also the timestamp since last publishing is updated.
Definition at line 33 of file visualization_daemon.cpp.
| void VisDaemon::ROSAGVPositionCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Callback function for incoming ROSAGVPosition messages.
| msg | Incoming message. |
Definition at line 105 of file visualization_daemon.cpp.
| void VisDaemon::ROSVelocityCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Callback function for incoming ROS velocity messages.
| msg | Incoming message. |
Definition at line 121 of file visualization_daemon.cpp.
| void VisDaemon::UpdateVisualization | ( | ) |
Main loop of the vis daemon. Does all the processing between receiving and publishing messages.
Definition at line 43 of file visualization_daemon.cpp.
|
private |
Timestamp of the last sent message.
Definition at line 59 of file visualization_daemon.h.
|
private |
ROS Publisher for sending out visualization messages.
Definition at line 53 of file visualization_daemon.h.
|
private |
Time interval for sending out visualization messages.
Definition at line 56 of file visualization_daemon.h.
|
private |
ROS Message object for repeated use (sending visualization messages to the fleet controller.
Definition at line 49 of file visualization_daemon.h.