src/daemon.cpp
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 
11 #include <iostream>
12 #include <vector>
13 #include <string>
14 
15 
16 
17 /*
18  * TODO: publish to topicPub, if following requirements are met:
19  * - received order
20  * - received order update
21  * - change of load status
22  * - error
23  * - driving over an node
24  * - change in operationMode
25  * - change in "driving" field of the state
26  * - change in nodeStates, edgeStates or actionStates
27  * - every 30 seconds if nothing changed
28  */
29 
31 {
32  testMode=true;
33 }
34 
35 Daemon::Daemon(ros::NodeHandle *nh,std::string daemonName)
36 {
37  testMode=false;
40  topicPublisherList=ReadTopicParams(nh,daemonName +"/topics_publish");
41  topicSubscriberList=ReadTopicParams(nh,daemonName +"/topics_subscribe");
43 }
44 
45 
46 std::map<std::string,std::string> Daemon::GetTopicPublisherList()
47 {
48  return topicPublisherList;
49 }
50 
51 std::map<std::string,std::string> Daemon::GetTopicSubscriberList()
52 {
53  return topicSubscriberList;
54 }
55 
56 std::vector<std::string> Daemon::GetMsgList(std::map<std::string,std::string> topicList)
57 {
58  std::vector<std::string> msgList;
59  for(const auto& elem : topicList)
60  msgList.push_back(elem.first);
61  return msgList;
62 }
63 
64 std::string Daemon::GetParameter(std::string paramName)
65  {
66  std::string paramValue="";
67  if (ros::param::has(paramName))
68  {
69  ros::param::get(paramName,paramValue);
70  ROS_INFO_STREAM("Using "<< paramValue << " for parameter " <<paramName);
71  }
72  else if (!testMode)
73  {
74  ROS_WARN_STREAM("ParamName "<< paramName <<" not found in YAML file. Replaced with empty string");
75  }
76  return paramValue;
77 }
78 
80 {
81  messageHeader.headerId = 0;
82  messageHeader.version = GetParameter("AGV_Data/version");
83  messageHeader.manufacturer = GetParameter("AGV_Data/manufacturer");
84  messageHeader.serialNumber = GetParameter("AGV_Data/serialNumber");
85 }
86 
88 {
89  vda5050_msgs::Header header = GetHeader();
90  std::stringstream ss;
91  ss << GetParameter("AGV_Data/interfaceName") << "/" << GetParameter("AGV_Data/majorVersion")<< "/" << messageHeader.manufacturer << "/" << messageHeader.serialNumber;
92  mqttTopicStructurePrefix = ss.str();
93 }
94 
96 {
97  return (mqttTopicStructurePrefix);
98 }
99 
101 {
102  messageHeader.timestamp = CreateTimestamp();
103  messageHeader.headerId += 1;
104 }
105 
106 vda5050_msgs::Header Daemon::GetHeader()
107 {
108  UpdateHeader();
109  return(messageHeader);
110 }
111 
112 bool Daemon::CompareStrings(std::string str1,std::string str2)
113 {
114  return(str1.find(str2) != std::string::npos ? true:false);
115 }
116 
117 bool Daemon::CheckTopic(std::string str1,std::string str2)
118 {
119  bool hasTopic=false;
120  if (!CompareStrings(str1,str2+"/"))
121  {
122  hasTopic=CompareStrings(str1,str2);
123  }
124  return (hasTopic);
125 
126 }
127 
128 std::string Daemon::GetTopic(std::string hierarchical_topic)
129 {
130  size_t last_slash = hierarchical_topic.find_last_of("/");
131  return hierarchical_topic.substr(last_slash+1);
132 }
133 
134 bool Daemon::CheckRange(double lowerRange, double upperRange, double value, std::string msg_name)
135 {
136  bool withinRange=false;
137  if (value < lowerRange || value > upperRange)
138  {
139  if (!testMode)
140  {
141  std_msgs::String errorMsg;
142  std::ostringstream ss;
143  if (value < lowerRange)
144  {
145  ss << msg_name << " msg undercut lower range. value: " << value << " < " << lowerRange;
146  }
147  else if (value > upperRange)
148  {
149  ss << msg_name << " msg exceeds upper range. value: " << value << " > " << upperRange;
150  }
151  errorMsg.data=ss.str();
152  errorPublisher.publish(errorMsg);
153  ROS_WARN_STREAM(errorMsg.data);
154  }
155  }
156  else
157  {
158  withinRange=true;
159  }
160  return withinRange;
161 }
162 
163 
164 std::map<std::string,std::string> Daemon::ReadTopicParams(ros::NodeHandle *nh,std::string paramName)
165 {
166  std::map<std::string,std::string> paramResults;
167  std::vector<std::string> keys;
168  nh->getParamNames(keys);
169  for(std::size_t i = 0; i < keys.size(); ++i)
170  {
171  if (CompareStrings(keys[i],paramName))
172  {
173  if (ros::param::has(keys[i]))
174  {
175  std::string returnValue;
176  ros::param::get(keys[i],returnValue);
177  if (!returnValue.empty())
178  {
179  paramResults[keys[i]]=returnValue;
180  }
181  }
182  else
183  {
184  ROS_INFO_STREAM(paramName <<" has no parameter, please check the config YAML");
185  }
186  }
187  }
188  ROS_INFO_STREAM("for "<< paramName << " use:");
189  for(const auto& elem : paramResults)
190  {
191  ROS_INFO_STREAM(" - parameter: "<<elem.first << " value: " << elem.second);
192  }
193  return(paramResults);
194 }
195 
197 {
198  std::string errorTopic;
199  ros::param::param<std::string>("topic_error", errorTopic, DEFAULT_ERROR_TOPIC);
200  errorPublisher=nh->advertise<std_msgs::String>(errorTopic, 1000);
201  ROS_INFO_STREAM("Using "<< errorTopic << " as error topic");
202 }
203 
205 {
206  boost::posix_time::ptime posixTime = ros::Time::now().toBoost();
207  std::string isoTimeStr = boost::posix_time::to_iso_extended_string(posixTime);
208  return(isoTimeStr);
209 }
Daemon::GetHeader
vda5050_msgs::Header GetHeader()
Definition: src/daemon.cpp:106
Daemon::GetTopicPublisherList
std::map< std::string, std::string > GetTopicPublisherList()
Definition: src/daemon.cpp:46
Daemon::InitHeaderInfo
void InitHeaderInfo()
Definition: src/daemon.cpp:79
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
Daemon::createTopicStructurePrefix
void createTopicStructurePrefix()
Definition: src/daemon.cpp:87
Daemon::errorPublisher
ros::Publisher errorPublisher
Definition: daemon.h:64
Daemon::GetParameter
std::string GetParameter(std::string param)
Definition: src/daemon.cpp:64
Daemon::CompareStrings
bool CompareStrings(std::string str1, std::string str2)
Definition: src/daemon.cpp:112
Daemon::testMode
bool testMode
Definition: daemon.h:49
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
Daemon::Daemon
Daemon()
Definition: src/daemon.cpp:30
Daemon::CreateTimestamp
std::string CreateTimestamp()
Definition: src/daemon.cpp:204
Daemon::getTopicStructurePrefix
std::string getTopicStructurePrefix()
Definition: src/daemon.cpp:95
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
Daemon::GetTopicSubscriberList
std::map< std::string, std::string > GetTopicSubscriberList()
Definition: src/daemon.cpp:51
Daemon::CheckRange
bool CheckRange(double lowerRange, double upperRange, double value, std::string msg_name)
Definition: src/daemon.cpp:134
Daemon::GetTopic
std::string GetTopic(std::string hierarchical_topic)
Definition: src/daemon.cpp:128
Daemon::LinkErrorTopics
void LinkErrorTopics(ros::NodeHandle *nh)
Definition: src/daemon.cpp:196
Daemon::messageHeader
vda5050_msgs::Header messageHeader
Definition: daemon.h:32
Daemon::GetMsgList
std::vector< std::string > GetMsgList(std::map< std::string, std::string > topicList)
Definition: src/daemon.cpp:56
TimeBase< Time, Duration >::toBoost
boost::posix_time::ptime toBoost() const
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
Daemon::nh
ros::NodeHandle nh
Definition: daemon.h:67
Daemon::topicPublisherList
std::map< std::string, std::string > topicPublisherList
Definition: daemon.h:35
ros::NodeHandle::getParamNames
bool getParamNames(std::vector< std::string > &keys) const
Daemon::ReadTopicParams
std::map< std::string, std::string > ReadTopicParams(ros::NodeHandle *nh, std::string paramTopicName)
Definition: src/daemon.cpp:164
Daemon::topicSubscriberList
std::map< std::string, std::string > topicSubscriberList
Definition: daemon.h:40
Daemon::UpdateHeader
void UpdateHeader()
Definition: src/daemon.cpp:100
ros::param::has
ROSCPP_DECL bool has(const std::string &key)
header
const std::string header
Daemon::mqttTopicStructurePrefix
std::string mqttTopicStructurePrefix
Definition: daemon.h:45
ros::NodeHandle
Daemon::CheckTopic
bool CheckTopic(std::string str1, std::string str2)
Definition: src/daemon.cpp:117
daemon.h
ros::Time::now
static Time now()
DEFAULT_ERROR_TOPIC
#define DEFAULT_ERROR_TOPIC
Definition: daemon.h:22


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