visualization_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 VIS_DAEMON_H
11 #define VIS_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 #include "vda5050_msgs/Visualization.h"
37 
46 class VisDaemon: public Daemon
47 {
48  private:
49  vda5050_msgs::Visualization visMessage;
63  public:
67  VisDaemon();
68 
75  bool CheckPassedTime();
76 
84 
92 
97  void PublishVisualization();
98 
103  void UpdateVisualization();
104 
110  double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr& msg);
111 
112  // ---- ALL THE CALLBACKS ----
118  void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr& msg);
119 
126  void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr& msg);
127 
134  void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr& msg);
135 
142  void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr& msg);
143 
149  void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr& msg);
150 
156  void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr& msg);
157 
164  void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr& msg);
165 
171  void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr& msg);
172 };
173 #endif
174 
ros::NodeHandle nh
Definition: daemon.h:67
ros::Publisher pub
void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr &msg)
void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr &msg)
void LinkPublishTopics(ros::NodeHandle *nh)
vda5050_msgs::Visualization visMessage
void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr &msg)
void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr &msg)
void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr &msg)
void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr &msg)
void UpdateVisualization()
void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Time lastUpdateTimestamp
void LinkSubscriptionTopics(ros::NodeHandle *nh)
Definition: daemon.h:29
ros::Duration updateInterval
void PublishVisualization()
double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr &msg)
void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr &msg)


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