Public Member Functions | Private Attributes | List of all members
VisDaemon Class Reference

#include <visualization_daemon.h>

Inheritance diagram for VisDaemon:
Inheritance graph
[legend]

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::PublishermessagePublisher
 
ros::NodeHandle nh
 
std::map< std::string, ros::Subscribersubscribers
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ VisDaemon()

VisDaemon::VisDaemon ( )

Standard Constructor.

Definition at line 18 of file visualization_daemon.cpp.

Member Function Documentation

◆ AGVPositionCallback()

void VisDaemon::AGVPositionCallback ( const vda5050_msgs::AGVPosition::ConstPtr &  msg)

Callback function for incoming position messages.

Parameters
msgIncoming message.

Definition at line 133 of file visualization_daemon.cpp.

◆ AGVPositionDeviationRangeCallback()

void VisDaemon::AGVPositionDeviationRangeCallback ( const std_msgs::Float64::ConstPtr &  msg)

Callback function for incoming information about the deviation range of the AGV's position.

Parameters
msgIncoming message.

Definition at line 155 of file visualization_daemon.cpp.

◆ AGVPositionInitializedCallback()

void VisDaemon::AGVPositionInitializedCallback ( const std_msgs::Bool::ConstPtr &  msg)

Callback function for the incoming notification when the AGV position was initialized.

Parameters
msgIncoming message.

Definition at line 144 of file visualization_daemon.cpp.

◆ AGVPositionLocalizationScoreCallback()

void VisDaemon::AGVPositionLocalizationScoreCallback ( const std_msgs::Float64::ConstPtr &  msg)

Callback function for incoming information about the localization score of the AGV.

Parameters
msgIncoming message.

Definition at line 148 of file visualization_daemon.cpp.

◆ AGVPositionMapDescriptionCallback()

void VisDaemon::AGVPositionMapDescriptionCallback ( const std_msgs::String::ConstPtr &  msg)

Callback function for incoming map description strings of the AGV's position.

Parameters
msgIncoming message.

Definition at line 163 of file visualization_daemon.cpp.

◆ AGVPositionMapIdCallback()

void VisDaemon::AGVPositionMapIdCallback ( const std_msgs::String::ConstPtr &  msg)

Callback function for incoming MapIDs of the AGV's position.

Parameters
msgIncoming message.

Definition at line 159 of file visualization_daemon.cpp.

◆ CalculateAgvOrientation()

double VisDaemon::CalculateAgvOrientation ( const nav_msgs::Odometry::ConstPtr &  msg)

Calculate the AGV's rotation from odometry data.

Parameters
msgOdometry message that should be used for calculation.

Definition at line 91 of file visualization_daemon.cpp.

◆ CheckPassedTime()

bool VisDaemon::CheckPassedTime ( )
Calculates the passed time between last update interval and now.
Returns
Returns true if passed time since last publish is greater than 30 seconds, else returns false.

Definition at line 27 of file visualization_daemon.cpp.

◆ LinkPublishTopics()

void VisDaemon::LinkPublishTopics ( ros::NodeHandle nh)

Creates the publisher for the required topics. The list of topics is extracted from the config file.

Parameters
nhPointer to the node handler.

Definition at line 50 of file visualization_daemon.cpp.

◆ LinkSubscriptionTopics()

void VisDaemon::LinkSubscriptionTopics ( ros::NodeHandle nh)

Creates the subscribers for the required topics. The list of topics is extracted from the config file.

Parameters
nhPointer to node handler.

Definition at line 67 of file visualization_daemon.cpp.

◆ PublishVisualization()

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.

◆ ROSAGVPositionCallback()

void VisDaemon::ROSAGVPositionCallback ( const nav_msgs::Odometry::ConstPtr &  msg)

Callback function for incoming ROSAGVPosition messages.

Parameters
msgIncoming message.

Definition at line 105 of file visualization_daemon.cpp.

◆ ROSVelocityCallback()

void VisDaemon::ROSVelocityCallback ( const nav_msgs::Odometry::ConstPtr &  msg)

Callback function for incoming ROS velocity messages.

Parameters
msgIncoming message.

Definition at line 121 of file visualization_daemon.cpp.

◆ UpdateVisualization()

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.

Member Data Documentation

◆ lastUpdateTimestamp

ros::Time VisDaemon::lastUpdateTimestamp
private

Timestamp of the last sent message.

Definition at line 59 of file visualization_daemon.h.

◆ pub

ros::Publisher VisDaemon::pub
private

ROS Publisher for sending out visualization messages.

Definition at line 53 of file visualization_daemon.h.

◆ updateInterval

ros::Duration VisDaemon::updateInterval
private

Time interval for sending out visualization messages.

Definition at line 56 of file visualization_daemon.h.

◆ visMessage

vda5050_msgs::Visualization VisDaemon::visMessage
private

ROS Message object for repeated use (sending visualization messages to the fleet controller.

Definition at line 49 of file visualization_daemon.h.


The documentation for this class was generated from the following files:


vda5050_connector
Author(s): Florian Rothmeyer , Florian Spiegel
autogenerated on Wed Mar 22 2023 02:38:56