include
vda5050_connector
connection_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 CONNECTION_DAEMON_H
11
#define CONNECTION_DAEMON_H
12
#include <
ros/ros.h
>
13
#include <string>
14
#include <
ros/console.h
>
15
#include <std_msgs/Bool.h>
16
#include "
daemon.h
"
17
#include "std_msgs/String.h"
18
#include "boost/date_time/posix_time/posix_time.hpp"
19
20
#include "vda5050_msgs/Connection.h"
21
22
26
class
ConnectionDaemon
:
public
Daemon
27
{
28
private
:
29
vda5050_msgs::Connection
connectionMessage
;
32
ros::Publisher
connectionPublisher
;
35
ros::Subscriber
connectionSubscriber
;
38
ros::Duration
updateInterval
;
43
ros::Time
lastUpdateTimestamp
;
46
public
:
52
ConnectionDaemon
(
float
heartbeat);
53
60
void
LinkSubscriptionTopics
(
ros::NodeHandle
*
nh
);
61
68
bool
CheckPassedTime
();
69
74
void
PublishConnection
();
75
80
void
UpdateConnection
();
81
86
std::string
createPublishTopic
();
87
94
void
ROSConnectionStateCallback
(
const
std_msgs::Bool::ConstPtr& msg);
95
};
96
#endif
97
ros::Publisher
ros.h
ConnectionDaemon::connectionSubscriber
ros::Subscriber connectionSubscriber
Definition:
connection_daemon.h:35
ConnectionDaemon::lastUpdateTimestamp
ros::Time lastUpdateTimestamp
Definition:
connection_daemon.h:43
console.h
ConnectionDaemon::ROSConnectionStateCallback
void ROSConnectionStateCallback(const std_msgs::Bool::ConstPtr &msg)
Definition:
connection_daemon.cpp:71
ConnectionDaemon::LinkSubscriptionTopics
void LinkSubscriptionTopics(ros::NodeHandle *nh)
Definition:
connection_daemon.cpp:28
ConnectionDaemon::PublishConnection
void PublishConnection()
Definition:
connection_daemon.cpp:51
ConnectionDaemon::UpdateConnection
void UpdateConnection()
Definition:
connection_daemon.cpp:63
Daemon::nh
ros::NodeHandle nh
Definition:
daemon.h:67
Daemon
Definition:
daemon.h:29
ConnectionDaemon::connectionPublisher
ros::Publisher connectionPublisher
Definition:
connection_daemon.h:32
ros::Time
ConnectionDaemon
Definition:
connection_daemon.h:26
ConnectionDaemon::updateInterval
ros::Duration updateInterval
Definition:
connection_daemon.h:38
ros::Duration
ConnectionDaemon::CheckPassedTime
bool CheckPassedTime()
Definition:
connection_daemon.cpp:45
ConnectionDaemon::connectionMessage
vda5050_msgs::Connection connectionMessage
Definition:
connection_daemon.h:29
ConnectionDaemon::createPublishTopic
std::string createPublishTopic()
Definition:
connection_daemon.cpp:38
ros::NodeHandle
ros::Subscriber
daemon.h
ConnectionDaemon::ConnectionDaemon
ConnectionDaemon(float heartbeat)
Definition:
connection_daemon.cpp:19
vda5050_connector
Author(s): Florian Rothmeyer
, Florian Spiegel
autogenerated on Wed Mar 22 2023 02:38:56