state_daemon.h
Go to the documentation of this file.
1 /*
2  * Copyright 2022 Technical University of Munich, Chair of Materials Handling,
3  * Material Flow, Logistics – All Rights Reserved
4  *
5  * You may use, distribute and modify this code under the terms of the 3-clause
6  * BSD license. You should have received a copy of that license with this file.
7  * If not, please write to {kontakt.fml@ed.tum.de}.
8  */
9 
10 #ifndef ORDER_DAEMON_H
11 #define ORDER_DAEMON_H
12 #include <ros/ros.h>
13 #include <string>
14 #include <ros/console.h>
15 #include <std_msgs/UInt32.h>
16 #include <std_msgs/Float64.h>
17 #include <std_msgs/Int8.h>
18 #include <std_msgs/Bool.h>
19 #include <nav_msgs/Odometry.h>
20 #include <sensor_msgs/BatteryState.h>
21 #include "daemon.h"
22 #include "std_msgs/String.h"
23 #include "boost/date_time/posix_time/posix_time.hpp"
24 
25 #include "vda5050_msgs/State.h"
26 #include "vda5050_msgs/NodeStates.h"
27 #include "vda5050_msgs/NodeState.h"
28 #include "vda5050_msgs/EdgeStates.h"
29 #include "vda5050_msgs/EdgeState.h"
30 #include "vda5050_msgs/AGVPosition.h"
31 #include "vda5050_msgs/Loads.h"
32 #include "vda5050_msgs/ActionStates.h"
33 #include "vda5050_msgs/Errors.h"
34 #include "vda5050_msgs/Information.h"
35 #include "vda5050_msgs/SafetyState.h"
36 
45 class StateDaemon: public Daemon
46 {
47  private:
48  vda5050_msgs::State stateMessage;
54  /* Declare all ROS subscriber and publisher topics for internal
55  * communication.
56  */
57 
71  public:
78  StateDaemon();
79 
86  bool CheckPassedTime();
87 
95 
103 
108  void PublishState();
109 
114  void UpdateState();
115 
123  double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr& msg);
124 
125  // ---- ALL THE CALLBACKS ----
126 
132  void OrderIdCallback(const std_msgs::String::ConstPtr& msg);
133 
139  void OrderUpdateIdCallback(const std_msgs::UInt32::ConstPtr& msg);
140 
146  void ZoneSetIdCallback(const std_msgs::String::ConstPtr& msg);
147 
153  void LastNodeIdCallback(const std_msgs::String::ConstPtr& msg);
154 
160  void LastNodeSequenceIdCallback(const std_msgs::UInt32::ConstPtr& msg);
161 
167  void NodeStatesCallback(const vda5050_msgs::NodeStates::ConstPtr& msg);
168 
174  void EdgeStatesCallback(const vda5050_msgs::EdgeStates::ConstPtr& msg);
175 
181  void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr& msg);
182 
189  void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr& msg);
190 
197  void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr& msg);
198 
205  void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr& msg);
206 
212  void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr& msg);
213 
219  void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr& msg);
220 
227  void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr& msg);
228 
234  void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr& msg);
235 
241  void LoadsCallback(const vda5050_msgs::Loads::ConstPtr& msg);
242 
249  void DrivingCallback(const std_msgs::Bool::ConstPtr& msg);
250 
257  void PausedCallback(const std_msgs::Bool::ConstPtr& msg);
258 
265  void NewBaseRequestCallback(const std_msgs::Bool::ConstPtr& msg);
266 
272  void DistanceSinceLastNodeCallback(const std_msgs::Float64::ConstPtr& msg);
273 
279  void ActionStateCallback(const vda5050_msgs::ActionState::ConstPtr& msg);
280 
286  void BatteryStateCallback(const vda5050_msgs::BatteryState::ConstPtr& msg);
287 
293  void BatteryStateBatteryHealthCallback(const std_msgs::Int8::ConstPtr& msg);
294 
301  void BatteryStateChargingCallback(const std_msgs::Bool::ConstPtr& msg);
302 
308  void BatteryStateReachCallback(const std_msgs::UInt32::ConstPtr& msg);
309 
315  void ROSBatteryInfoCallback(const sensor_msgs::BatteryState::ConstPtr& msg);
316 
323  void OperatingModeCallback(const std_msgs::String::ConstPtr& msg);
324 
330  void ErrorsCallback(const vda5050_msgs::Errors::ConstPtr& msg);
331 
337  void InformationCallback(const vda5050_msgs::Information::ConstPtr& msg);
338 
345  void SafetyStateCallback(const vda5050_msgs::SafetyState::ConstPtr& msg);
346 
353  void SafetyStateEstopCallback(const std_msgs::String::ConstPtr& msg);
354 
360  void SafetyStateFieldViolationCallback(const std_msgs::Bool::ConstPtr& msg);
361 };
362 #endif
363 
void BatteryStateReachCallback(const std_msgs::UInt32::ConstPtr &msg)
void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr &msg)
ros::Time lastUpdateTimestamp
Definition: state_daemon.h:64
ros::NodeHandle nh
Definition: daemon.h:67
void ROSBatteryInfoCallback(const sensor_msgs::BatteryState::ConstPtr &msg)
ros::Duration updateInterval
Definition: state_daemon.h:61
void EdgeStatesCallback(const vda5050_msgs::EdgeStates::ConstPtr &msg)
bool CheckPassedTime()
ros::Subscriber actionStatesSub
Definition: state_daemon.h:58
void SafetyStateCallback(const vda5050_msgs::SafetyState::ConstPtr &msg)
vda5050_msgs::State stateMessage
Definition: state_daemon.h:48
void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr &msg)
void LastNodeSequenceIdCallback(const std_msgs::UInt32::ConstPtr &msg)
void LoadsCallback(const vda5050_msgs::Loads::ConstPtr &msg)
void PausedCallback(const std_msgs::Bool::ConstPtr &msg)
void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr &msg)
void SafetyStateFieldViolationCallback(const std_msgs::Bool::ConstPtr &msg)
void ActionStateCallback(const vda5050_msgs::ActionState::ConstPtr &msg)
void BatteryStateCallback(const vda5050_msgs::BatteryState::ConstPtr &msg)
void LinkSubscriptionTopics(ros::NodeHandle *nh)
void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr &msg)
void InformationCallback(const vda5050_msgs::Information::ConstPtr &msg)
void UpdateState()
double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr &msg)
void LinkPublishTopics(ros::NodeHandle *nh)
void PublishState()
void NodeStatesCallback(const vda5050_msgs::NodeStates::ConstPtr &msg)
void ZoneSetIdCallback(const std_msgs::String::ConstPtr &msg)
void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr &msg)
void OrderUpdateIdCallback(const std_msgs::UInt32::ConstPtr &msg)
void BatteryStateBatteryHealthCallback(const std_msgs::Int8::ConstPtr &msg)
Definition: daemon.h:29
void DrivingCallback(const std_msgs::Bool::ConstPtr &msg)
void OperatingModeCallback(const std_msgs::String::ConstPtr &msg)
void NewBaseRequestCallback(const std_msgs::Bool::ConstPtr &msg)
void SafetyStateEstopCallback(const std_msgs::String::ConstPtr &msg)
bool newPublishTrigger
Definition: state_daemon.h:67
void ErrorsCallback(const vda5050_msgs::Errors::ConstPtr &msg)
void OrderIdCallback(const std_msgs::String::ConstPtr &msg)
void BatteryStateChargingCallback(const std_msgs::Bool::ConstPtr &msg)
ros::Publisher pub
Definition: state_daemon.h:51
void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr &msg)
void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr &msg)
void LastNodeIdCallback(const std_msgs::String::ConstPtr &msg)
void DistanceSinceLastNodeCallback(const std_msgs::Float64::ConstPtr &msg)
void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr &msg)


vda5050_connector
Author(s): Florian Rothmeyer , Florian Spiegel
autogenerated on Tue Mar 21 2023 02:52:00