#include <state_daemon.h>

Public Member Functions | |
| void | ActionStateCallback (const vda5050_msgs::ActionState::ConstPtr &msg) |
| 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) |
| void | BatteryStateBatteryHealthCallback (const std_msgs::Int8::ConstPtr &msg) |
| void | BatteryStateCallback (const vda5050_msgs::BatteryState::ConstPtr &msg) |
| void | BatteryStateChargingCallback (const std_msgs::Bool::ConstPtr &msg) |
| void | BatteryStateReachCallback (const std_msgs::UInt32::ConstPtr &msg) |
| double | CalculateAgvOrientation (const nav_msgs::Odometry::ConstPtr &msg) |
| bool | CheckPassedTime () |
| void | DistanceSinceLastNodeCallback (const std_msgs::Float64::ConstPtr &msg) |
| void | DrivingCallback (const std_msgs::Bool::ConstPtr &msg) |
| void | EdgeStatesCallback (const vda5050_msgs::EdgeStates::ConstPtr &msg) |
| void | ErrorsCallback (const vda5050_msgs::Errors::ConstPtr &msg) |
| void | InformationCallback (const vda5050_msgs::Information::ConstPtr &msg) |
| void | LastNodeIdCallback (const std_msgs::String::ConstPtr &msg) |
| void | LastNodeSequenceIdCallback (const std_msgs::UInt32::ConstPtr &msg) |
| void | LinkPublishTopics (ros::NodeHandle *nh) |
| void | LinkSubscriptionTopics (ros::NodeHandle *nh) |
| void | LoadsCallback (const vda5050_msgs::Loads::ConstPtr &msg) |
| void | NewBaseRequestCallback (const std_msgs::Bool::ConstPtr &msg) |
| void | NodeStatesCallback (const vda5050_msgs::NodeStates::ConstPtr &msg) |
| void | OperatingModeCallback (const std_msgs::String::ConstPtr &msg) |
| void | OrderIdCallback (const std_msgs::String::ConstPtr &msg) |
| void | OrderUpdateIdCallback (const std_msgs::UInt32::ConstPtr &msg) |
| void | PausedCallback (const std_msgs::Bool::ConstPtr &msg) |
| void | PublishState () |
| void | ROSAGVPositionCallback (const nav_msgs::Odometry::ConstPtr &msg) |
| void | ROSBatteryInfoCallback (const sensor_msgs::BatteryState::ConstPtr &msg) |
| void | ROSVelocityCallback (const nav_msgs::Odometry::ConstPtr &msg) |
| void | SafetyStateCallback (const vda5050_msgs::SafetyState::ConstPtr &msg) |
| void | SafetyStateEstopCallback (const std_msgs::String::ConstPtr &msg) |
| void | SafetyStateFieldViolationCallback (const std_msgs::Bool::ConstPtr &msg) |
| StateDaemon () | |
| void | UpdateState () |
| void | ZoneSetIdCallback (const std_msgs::String::ConstPtr &msg) |
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::Subscriber | actionStatesSub |
| ros::Time | lastUpdateTimestamp |
| bool | newPublishTrigger |
| ros::Publisher | pub |
| vda5050_msgs::State | stateMessage |
| 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 state 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 45 of file state_daemon.h.
| StateDaemon::StateDaemon | ( | ) |
Standard Constructor.
| nh | Pointer to nodehandler. |
| daemonName | Name of the daemon. |
TODO: publish to topicPub, if following requirements are met:
Definition at line 27 of file state_daemon.cpp.
| void StateDaemon::ActionStateCallback | ( | const vda5050_msgs::ActionState::ConstPtr & | msg | ) |
Callback function that receives new states of actions.
| msg | Incoming message. |
TODO: Use single action states
Definition at line 283 of file state_daemon.cpp.
| void StateDaemon::AGVPositionCallback | ( | const vda5050_msgs::AGVPosition::ConstPtr & | msg | ) |
Callback function for incoming AGV positions.
| msg | Incoming message. |
Definition at line 226 of file state_daemon.cpp.
| void StateDaemon::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 248 of file state_daemon.cpp.
| void StateDaemon::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 237 of file state_daemon.cpp.
| void StateDaemon::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 241 of file state_daemon.cpp.
| void StateDaemon::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 256 of file state_daemon.cpp.
| void StateDaemon::AGVPositionMapIdCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function for incoming MapIDs of the AGV's position.
| msg | Incoming message. |
Definition at line 252 of file state_daemon.cpp.
| void StateDaemon::BatteryStateBatteryHealthCallback | ( | const std_msgs::Int8::ConstPtr & | msg | ) |
Callback function that receives information about the battery health.
| msg | Incoming message. |
Definition at line 296 of file state_daemon.cpp.
| void StateDaemon::BatteryStateCallback | ( | const vda5050_msgs::BatteryState::ConstPtr & | msg | ) |
Callback function that receives new battery state messages.
| msg | Incoming message. |
Definition at line 288 of file state_daemon.cpp.
| void StateDaemon::BatteryStateChargingCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback function that is called when the vehicle starts or stops charging its battery.
| msg | Incoming message. |
Definition at line 300 of file state_daemon.cpp.
| void StateDaemon::BatteryStateReachCallback | ( | const std_msgs::UInt32::ConstPtr & | msg | ) |
Callback function for incoming updates about the reach of the battery.
| msg | Incoming message. |
Definition at line 304 of file state_daemon.cpp.
| double StateDaemon::CalculateAgvOrientation | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Calculate the vehicle's orientation.
| msg | Odometry message containing implicit pose data. |
Definition at line 149 of file state_daemon.cpp.
| bool StateDaemon::CheckPassedTime | ( | ) |
Calculates the passed time between last update interval and now.
Definition at line 40 of file state_daemon.cpp.
| void StateDaemon::DistanceSinceLastNodeCallback | ( | const std_msgs::Float64::ConstPtr & | msg | ) |
Callback function that receives the updated distance since the last node.
| msg | Incoming message. |
Definition at line 279 of file state_daemon.cpp.
| void StateDaemon::DrivingCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback function for incoming messages about the vehicle's driving status.
| msg | Incoming message. |
Definition at line 266 of file state_daemon.cpp.
| void StateDaemon::EdgeStatesCallback | ( | const vda5050_msgs::EdgeStates::ConstPtr & | msg | ) |
Callback function for incoming EdgeStates.
| msg | Incoming message. |
Definition at line 222 of file state_daemon.cpp.
| void StateDaemon::ErrorsCallback | ( | const vda5050_msgs::Errors::ConstPtr & | msg | ) |
Callback function that receives error messages.
| msg | Incoming message. |
Definition at line 313 of file state_daemon.cpp.
| void StateDaemon::InformationCallback | ( | const vda5050_msgs::Information::ConstPtr & | msg | ) |
Callback function that receives general information messages.
| msg | Incoming message. |
Definition at line 318 of file state_daemon.cpp.
| void StateDaemon::LastNodeIdCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function for incoming LastNodeIDs.
| msg | Incoming message. |
Definition at line 210 of file state_daemon.cpp.
| void StateDaemon::LastNodeSequenceIdCallback | ( | const std_msgs::UInt32::ConstPtr & | msg | ) |
Callback function for incoming LastNodeSequenceIDs.
| msg | Incoming message. |
Definition at line 214 of file state_daemon.cpp.
| void StateDaemon::LinkPublishTopics | ( | ros::NodeHandle * | nh | ) |
Creates the publisher for the required topics given from the config file.
| nh | Pointer to the node handler. |
Definition at line 60 of file state_daemon.cpp.
| void StateDaemon::LinkSubscriptionTopics | ( | ros::NodeHandle * | nh | ) |
Creates the subscribers for the required topics given from the config file.
| nh | Pointer to node handler. |
Definition at line 76 of file state_daemon.cpp.
| void StateDaemon::LoadsCallback | ( | const vda5050_msgs::Loads::ConstPtr & | msg | ) |
Callback function for incoming Load messages.
| msg | Incoming message. |
Definition at line 261 of file state_daemon.cpp.
| void StateDaemon::NewBaseRequestCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback function for notifying this daemon when a new base was requested.
| msg | Incoming message. |
Definition at line 275 of file state_daemon.cpp.
| void StateDaemon::NodeStatesCallback | ( | const vda5050_msgs::NodeStates::ConstPtr & | msg | ) |
Callback function for incoming NodeStates.
| msg | Incoming message. |
Definition at line 218 of file state_daemon.cpp.
| void StateDaemon::OperatingModeCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function that is called when the operating mode of the vehicle changes.
| msg | Incoming message. |
Definition at line 308 of file state_daemon.cpp.
| void StateDaemon::OrderIdCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function for incoming OrderIDs.
| msg | Incoming message. |
Definition at line 198 of file state_daemon.cpp.
| void StateDaemon::OrderUpdateIdCallback | ( | const std_msgs::UInt32::ConstPtr & | msg | ) |
Callback function for incoming OrderUpdateIDs.
| msg | Incoming message. |
Definition at line 202 of file state_daemon.cpp.
| void StateDaemon::PausedCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback function for notifying this daemon when the vehicle pauses or resumes.
| msg | Incoming message. |
Definition at line 271 of file state_daemon.cpp.
| void StateDaemon::PublishState | ( | ) |
Fetches the header message and publishes the state message. Updates the timestamp since last publishing.
Definition at line 46 of file state_daemon.cpp.
| void StateDaemon::ROSAGVPositionCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Callback function for incoming ROSAGVPosition messages.
| msg | Incoming message. |
Definition at line 163 of file state_daemon.cpp.
| void StateDaemon::ROSBatteryInfoCallback | ( | const sensor_msgs::BatteryState::ConstPtr & | msg | ) |
Callback function for incoming ROS battery information messages.
| msg | Incoming message. |
Definition at line 191 of file state_daemon.cpp.
| void StateDaemon::ROSVelocityCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Callback function for incoming ROS velocity messages.
| msg | Incoming message. |
Definition at line 179 of file state_daemon.cpp.
| void StateDaemon::SafetyStateCallback | ( | const vda5050_msgs::SafetyState::ConstPtr & | msg | ) |
Callback function that is called when the safety state of the vehicle changes.
| msg | Incoming message. |
Definition at line 322 of file state_daemon.cpp.
| void StateDaemon::SafetyStateEstopCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function that is called when the emergency stop of the vehicle was triggered.
| msg | Incoming message. |
Definition at line 327 of file state_daemon.cpp.
| void StateDaemon::SafetyStateFieldViolationCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback function for notification about safety field violations.
| msg | Incoming message. |
Definition at line 331 of file state_daemon.cpp.
| void StateDaemon::UpdateState | ( | ) |
Checks all the logic within the state daemon. For example, it checks if 30 seconds have passed without update.
Definition at line 53 of file state_daemon.cpp.
| void StateDaemon::ZoneSetIdCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Callback function for incoming ZoneSetIDs.
| msg | Incoming message. |
Definition at line 206 of file state_daemon.cpp.
|
private |
states of actions from action_daemon to state_daemon.
Definition at line 58 of file state_daemon.h.
|
private |
Timestamp of the last emitted state message.
Definition at line 64 of file state_daemon.h.
|
private |
Flag for initiating the emission of a new state message.
Definition at line 67 of file state_daemon.h.
|
private |
Publisher object for state messages to the fleet controller.
Definition at line 51 of file state_daemon.h.
|
private |
TODO: What is this used for?
Definition at line 48 of file state_daemon.h.
|
private |
Time interval for emitting state messages.
Definition at line 61 of file state_daemon.h.