state_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 
27 StateDaemon::StateDaemon() : Daemon(&(this->nh), "state_daemon")
28 {
29  LinkPublishTopics(&(this->nh));
30  LinkSubscriptionTopics(&(this->nh));
31 
32  // Initialize internal topics
33  actionStatesSub = nh.subscribe("actionStates", 1000, &StateDaemon::ActionStateCallback, this);
34 
37  newPublishTrigger=true;
38 }
39 
41 {
43  return(passedTime >= updateInterval ? true:false);
44 }
45 
47 {
48  stateMessage.header=GetHeader();
49  messagePublisher["/state"].publish(stateMessage);
51  newPublishTrigger=false;
52 }
54 {
56  {
57  PublishState();
58  }
59 }
61 {
62  std::map<std::string,std::string>topicList=GetTopicPublisherList();
63  std::stringstream ss;
65 
66  for(const auto& elem : topicList)
67  {
68  ss<< "/" << elem.second;
69  if (CheckTopic(elem.first,"state"))
70  {
71  messagePublisher[elem.second]=nh->advertise<vda5050_msgs::State>(ss.str(),1000);
72  }
73  }
74 }
75 
77 {
78  std::map<std::string,std::string>topicList=GetTopicSubscriberList();
79  for(const auto& elem : topicList)
80  {
81  // TODO make shorter via switch/case or a map from string to callback function
82  if (CheckTopic(elem.first,"orderId"))
83  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::OrderIdCallback, this);
84  else if (CheckTopic(elem.first,"orderUpdateId"))
85  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::OrderUpdateIdCallback, this);
86  else if (CheckTopic(elem.first,"zoneSetId"))
87  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::ZoneSetIdCallback, this);
88  else if (CheckTopic(elem.first,"lastNodeId"))
89  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::LastNodeIdCallback, this);
90  else if (CheckTopic(elem.first,"lastNodeSequenceId"))
91  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::LastNodeSequenceIdCallback, this);
92  else if (CheckTopic(elem.first,"nodeStates"))
93  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::NodeStatesCallback, this);
94  else if (CheckTopic(elem.first,"edgeStates"))
95  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::EdgeStatesCallback, this);
96  else if (CheckTopic(elem.first,"agvPosition"))
97  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::AGVPositionCallback, this);
98  else if (CheckTopic(elem.first,"positionInitialized"))
99  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::AGVPositionInitializedCallback, this);
100  else if (CheckTopic(elem.first,"localizationScore"))
101  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::AGVPositionLocalizationScoreCallback, this);
102  else if (CheckTopic(elem.first,"deviationRange"))
103  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::AGVPositionDeviationRangeCallback, this);
104  else if (CheckTopic(elem.first,"pose"))
105  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::ROSAGVPositionCallback, this);
106  else if (CheckTopic(elem.first,"mapId"))
107  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::AGVPositionMapIdCallback, this);
108  else if (CheckTopic(elem.first,"mapDescription"))
109  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::AGVPositionMapDescriptionCallback, this);
110  else if (CheckTopic(elem.first,"velocity"))
111  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::ROSVelocityCallback, this);
112  else if (CheckTopic(elem.first,"loads"))
113  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::LoadsCallback, this);
114  else if (CheckTopic(elem.first,"driving"))
115  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::DrivingCallback, this);
116  else if (CheckTopic(elem.first,"paused"))
117  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::PausedCallback, this);
118  else if (CheckTopic(elem.first,"newBaseRequest"))
119  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::NewBaseRequestCallback, this);
120  else if (CheckTopic(elem.first,"distanceSinceLastNode"))
121  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::DistanceSinceLastNodeCallback, this);
122  else if (CheckTopic(elem.first,"actionStates"))
123  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::ActionStateCallback, this);
124  else if (CheckTopic(elem.first,"batteryState"))
125  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::BatteryStateCallback, this);
126  else if (CheckTopic(elem.first,"batteryCharge"))
127  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::ROSBatteryInfoCallback, this);
128  else if (CheckTopic(elem.first,"batteryHealth"))
129  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::BatteryStateBatteryHealthCallback, this);
130  else if (CheckTopic(elem.first,"charging"))
131  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::BatteryStateChargingCallback, this);
132  else if (CheckTopic(elem.first,"reach"))
133  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::BatteryStateReachCallback, this);
134  else if (CheckTopic(elem.first,"operatingMode"))
135  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::OperatingModeCallback, this);
136  else if (CheckTopic(elem.first,"errors"))
137  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::ErrorsCallback, this);
138  else if (CheckTopic(elem.first,"information"))
139  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::InformationCallback, this);
140  else if (CheckTopic(elem.first,"safetyState"))
141  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::SafetyStateCallback, this);
142  else if (CheckTopic(elem.first,"eStop"))
143  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::SafetyStateEstopCallback, this);
144  else if (CheckTopic(elem.first,"fieldViolation"))
145  subscribers[elem.first]=nh->subscribe(elem.second,1000,&StateDaemon::SafetyStateFieldViolationCallback, this);
146  }
147 }
148 
149 double StateDaemon::CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr& msg)
150 {
151  tf::Quaternion q(
152  msg->pose.pose.orientation.x,
153  msg->pose.pose.orientation.y,
154  msg->pose.pose.orientation.z,
155  msg->pose.pose.orientation.w);
156  tf::Matrix3x3 m(q);
157  double roll, pitch, yaw;
158  m.getRPY(roll,pitch,yaw);
159  return (yaw);
160 }
161 
162 //ROS specific callbacks
163 void StateDaemon::ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr& msg)
164 {
165  /* TODO: check if transformation is correct, e.g. missing rotation
166  * to transform ros to vda 5050 this might help:
167  * vda5050.x=ros.y*(-1)
168  * vda5050.y=ros.x
169  */
170  double theta;
171  stateMessage.agvPosition.x=msg->pose.pose.position.x;
172  stateMessage.agvPosition.y=msg->pose.pose.position.y;
173  theta=CalculateAgvOrientation(msg);
174  if (CheckRange(-M_PI,M_PI,theta,"theta"))
175  {
176  stateMessage.agvPosition.theta=theta;
177  }
178 }
179 void StateDaemon::ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr& msg)
180 {
181  // local AGV based coordinate system ist the same as ros coordindat system, no transformation required
182  double omega;
183  stateMessage.velocity.vx=msg->twist.twist.linear.x;
184  stateMessage.velocity.vy=msg->twist.twist.linear.y;
185  if (CheckRange(-M_PI,M_PI,omega,"omega"))
186  {
187  stateMessage.velocity.omega=msg->twist.twist.angular.z;
188  }
189 }
190 
191 void StateDaemon::ROSBatteryInfoCallback(const sensor_msgs::BatteryState::ConstPtr& msg)
192 {
193  stateMessage.batteryState.batteryCharge=msg->percentage*100.0;
194  stateMessage.batteryState.batteryVoltage=msg->voltage;
195 }
196 
197 // VDA 5050 specific callbacks
198 void StateDaemon::OrderIdCallback(const std_msgs::String::ConstPtr& msg)
199 {
200  stateMessage.orderId=msg->data;
201 }
202 void StateDaemon::OrderUpdateIdCallback(const std_msgs::UInt32::ConstPtr& msg)
203 {
204  stateMessage.orderUpdateId=msg->data;
205 }
206 void StateDaemon::ZoneSetIdCallback(const std_msgs::String::ConstPtr& msg)
207 {
208  stateMessage.zoneSetId=msg->data;
209 }
210 void StateDaemon::LastNodeIdCallback(const std_msgs::String::ConstPtr& msg)
211 {
212  stateMessage.lastNodeId=msg->data;
213 }
214 void StateDaemon::LastNodeSequenceIdCallback(const std_msgs::UInt32::ConstPtr& msg)
215 {
216  stateMessage.lastNodeSequenceId=msg->data;
217 }
218 void StateDaemon::NodeStatesCallback(const vda5050_msgs::NodeStates::ConstPtr& msg)
219 {
220  stateMessage.nodeStates=msg->nodeStates;
221 }
222 void StateDaemon::EdgeStatesCallback(const vda5050_msgs::EdgeStates::ConstPtr& msg)
223 {
224  stateMessage.edgeStates=msg->edgeStates;
225 }
226 void StateDaemon::AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr& msg)
227 {
228  stateMessage.agvPosition.positionInitialized=msg->positionInitialized;
229  stateMessage.agvPosition.localizationScore=msg->localizationScore;
230  stateMessage.agvPosition.deviationRange=msg->deviationRange;
231  stateMessage.agvPosition.x=msg->x;
232  stateMessage.agvPosition.y=msg->y;
233  stateMessage.agvPosition.theta=msg->theta;
234  stateMessage.agvPosition.mapId=msg->mapId;
235  stateMessage.agvPosition.mapDescription=msg->mapDescription;
236 }
237 void StateDaemon::AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr& msg)
238 {
239  stateMessage.agvPosition.positionInitialized=msg->data;
240 }
241 void StateDaemon::AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr& msg)
242 {
243  if (CheckRange(0.0,1.0,msg->data,"AGV Position Localization Score"))
244  {
245  stateMessage.agvPosition.localizationScore=msg->data;
246  }
247 }
248 void StateDaemon::AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr& msg)
249 {
250  stateMessage.agvPosition.deviationRange=msg->data;
251 }
252 void StateDaemon::AGVPositionMapIdCallback(const std_msgs::String::ConstPtr& msg)
253 {
254  stateMessage.agvPosition.mapId=msg->data;
255 }
256 void StateDaemon::AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr& msg)
257 {
258  stateMessage.agvPosition.mapDescription=msg->data;
259 }
260 
261 void StateDaemon::LoadsCallback(const vda5050_msgs::Loads::ConstPtr& msg)
262 {
263  stateMessage.loads=msg->loads;
264  newPublishTrigger=true;
265 }
266 void StateDaemon::DrivingCallback(const std_msgs::Bool::ConstPtr& msg)
267 {
268  stateMessage.driving=msg->data;
269  newPublishTrigger=true;
270 }
271 void StateDaemon::PausedCallback(const std_msgs::Bool::ConstPtr& msg)
272 {
273  stateMessage.paused=msg->data;
274 }
275 void StateDaemon::NewBaseRequestCallback(const std_msgs::Bool::ConstPtr& msg)
276 {
277  stateMessage.newBaseRequest=msg->data;
278 }
279 void StateDaemon::DistanceSinceLastNodeCallback(const std_msgs::Float64::ConstPtr& msg)
280 {
281  stateMessage.distanceSinceLastNode=msg->data;
282 }
283 void StateDaemon::ActionStateCallback(const vda5050_msgs::ActionState::ConstPtr& msg)
284 {
286  // stateMessage.actionStates=msg->actionStates;
287 }
288 void StateDaemon::BatteryStateCallback(const vda5050_msgs::BatteryState::ConstPtr& msg)
289 {
290  stateMessage.batteryState.batteryHealth=msg->batteryHealth;
291  stateMessage.batteryState.batteryCharge=msg->batteryCharge;
292  stateMessage.batteryState.batteryVoltage=msg->batteryVoltage;
293  stateMessage.batteryState.charging=msg->charging;
294  stateMessage.batteryState.reach=msg->reach;
295 }
296 void StateDaemon::BatteryStateBatteryHealthCallback(const std_msgs::Int8::ConstPtr& msg)
297 {
298  stateMessage.batteryState.batteryHealth=msg->data;
299 }
300 void StateDaemon::BatteryStateChargingCallback(const std_msgs::Bool::ConstPtr& msg)
301 {
302  stateMessage.batteryState.charging=msg->data;
303 }
304 void StateDaemon::BatteryStateReachCallback(const std_msgs::UInt32::ConstPtr& msg)
305 {
306  stateMessage.batteryState.reach=msg->data;
307 }
308 void StateDaemon::OperatingModeCallback(const std_msgs::String::ConstPtr& msg)
309 {
310  stateMessage.operatingMode=msg->data;
311  newPublishTrigger=true;
312 }
313 void StateDaemon::ErrorsCallback(const vda5050_msgs::Errors::ConstPtr& msg)
314 {
315  stateMessage.errors=msg->errors;
316  newPublishTrigger=true;
317 }
318 void StateDaemon::InformationCallback(const vda5050_msgs::Information::ConstPtr& msg)
319 {
320  stateMessage.informations=msg->informations;
321 }
322 void StateDaemon::SafetyStateCallback(const vda5050_msgs::SafetyState::ConstPtr& msg)
323 {
324  stateMessage.safetyState.eStop=msg->eStop;
325  stateMessage.safetyState.fieldViolation=msg->fieldViolation;
326 }
327 void StateDaemon::SafetyStateEstopCallback(const std_msgs::String::ConstPtr& msg)
328 {
329  stateMessage.safetyState.eStop=msg->data;
330 }
331 void StateDaemon::SafetyStateFieldViolationCallback(const std_msgs::Bool::ConstPtr& msg)
332 {
333  stateMessage.safetyState.fieldViolation=msg->data;
334 }
335 
336 
337 
338 int main(int argc, char **argv)
339 {
340  ros::init(argc, argv, "state_deamon");
341 
342  StateDaemon stateDaemon;
343 
344  while(ros::ok())
345  {
346  stateDaemon.UpdateState();
347  ros::spinOnce();
348  }
349  return 0;
350 }
351 
352 
353 
354 
355 
356 
StateDaemon::StateDaemon
StateDaemon()
Definition: state_daemon.cpp:27
StateDaemon::stateMessage
vda5050_msgs::State stateMessage
Definition: state_daemon.h:48
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
StateDaemon::AGVPositionMapDescriptionCallback
void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:256
StateDaemon::AGVPositionInitializedCallback
void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: state_daemon.cpp:237
StateDaemon::BatteryStateReachCallback
void BatteryStateReachCallback(const std_msgs::UInt32::ConstPtr &msg)
Definition: state_daemon.cpp:304
StateDaemon::ROSAGVPositionCallback
void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: state_daemon.cpp:163
StateDaemon::DistanceSinceLastNodeCallback
void DistanceSinceLastNodeCallback(const std_msgs::Float64::ConstPtr &msg)
Definition: state_daemon.cpp:279
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
StateDaemon::AGVPositionLocalizationScoreCallback
void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr &msg)
Definition: state_daemon.cpp:241
StateDaemon::updateInterval
ros::Duration updateInterval
Definition: state_daemon.h:61
Daemon::subscribers
std::map< std::string, ros::Subscriber > subscribers
Definition: daemon.h:59
ros::spinOnce
ROSCPP_DECL void spinOnce()
StateDaemon::lastUpdateTimestamp
ros::Time lastUpdateTimestamp
Definition: state_daemon.h:64
state_daemon.h
StateDaemon::BatteryStateCallback
void BatteryStateCallback(const vda5050_msgs::BatteryState::ConstPtr &msg)
Definition: state_daemon.cpp:288
StateDaemon::LastNodeSequenceIdCallback
void LastNodeSequenceIdCallback(const std_msgs::UInt32::ConstPtr &msg)
Definition: state_daemon.cpp:214
StateDaemon::AGVPositionCallback
void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr &msg)
Definition: state_daemon.cpp:226
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
StateDaemon::SafetyStateCallback
void SafetyStateCallback(const vda5050_msgs::SafetyState::ConstPtr &msg)
Definition: state_daemon.cpp:322
ros::ok
ROSCPP_DECL bool ok()
StateDaemon::LinkPublishTopics
void LinkPublishTopics(ros::NodeHandle *nh)
Definition: state_daemon.cpp:60
Daemon::getTopicStructurePrefix
std::string getTopicStructurePrefix()
Definition: src/daemon.cpp:95
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
StateDaemon::CalculateAgvOrientation
double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr &msg)
Definition: state_daemon.cpp:149
StateDaemon::NodeStatesCallback
void NodeStatesCallback(const vda5050_msgs::NodeStates::ConstPtr &msg)
Definition: state_daemon.cpp:218
StateDaemon::ZoneSetIdCallback
void ZoneSetIdCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:206
StateDaemon::AGVPositionMapIdCallback
void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:252
StateDaemon::LinkSubscriptionTopics
void LinkSubscriptionTopics(ros::NodeHandle *nh)
Definition: state_daemon.cpp:76
StateDaemon::LoadsCallback
void LoadsCallback(const vda5050_msgs::Loads::ConstPtr &msg)
Definition: state_daemon.cpp:261
StateDaemon::ROSVelocityCallback
void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: state_daemon.cpp:179
StateDaemon::PausedCallback
void PausedCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: state_daemon.cpp:271
StateDaemon::SafetyStateFieldViolationCallback
void SafetyStateFieldViolationCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: state_daemon.cpp:331
Daemon::messagePublisher
std::map< std::string, ros::Publisher > messagePublisher
Definition: daemon.h:54
StateDaemon::BatteryStateBatteryHealthCallback
void BatteryStateBatteryHealthCallback(const std_msgs::Int8::ConstPtr &msg)
Definition: state_daemon.cpp:296
StateDaemon::InformationCallback
void InformationCallback(const vda5050_msgs::Information::ConstPtr &msg)
Definition: state_daemon.cpp:318
main
int main(int argc, char **argv)
Definition: state_daemon.cpp:338
StateDaemon::ActionStateCallback
void ActionStateCallback(const vda5050_msgs::ActionState::ConstPtr &msg)
Definition: state_daemon.cpp:283
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
StateDaemon::NewBaseRequestCallback
void NewBaseRequestCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: state_daemon.cpp:275
Daemon::nh
ros::NodeHandle nh
Definition: daemon.h:67
Daemon
Definition: daemon.h:29
StateDaemon::UpdateState
void UpdateState()
Definition: state_daemon.cpp:53
StateDaemon::PublishState
void PublishState()
Definition: state_daemon.cpp:46
StateDaemon::OrderUpdateIdCallback
void OrderUpdateIdCallback(const std_msgs::UInt32::ConstPtr &msg)
Definition: state_daemon.cpp:202
StateDaemon::SafetyStateEstopCallback
void SafetyStateEstopCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:327
StateDaemon::DrivingCallback
void DrivingCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: state_daemon.cpp:266
StateDaemon::OperatingModeCallback
void OperatingModeCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:308
StateDaemon::OrderIdCallback
void OrderIdCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:198
StateDaemon::AGVPositionDeviationRangeCallback
void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr &msg)
Definition: state_daemon.cpp:248
ros::Duration
StateDaemon::BatteryStateChargingCallback
void BatteryStateChargingCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: state_daemon.cpp:300
StateDaemon::newPublishTrigger
bool newPublishTrigger
Definition: state_daemon.h:67
StateDaemon::ROSBatteryInfoCallback
void ROSBatteryInfoCallback(const sensor_msgs::BatteryState::ConstPtr &msg)
Definition: state_daemon.cpp:191
StateDaemon::ErrorsCallback
void ErrorsCallback(const vda5050_msgs::Errors::ConstPtr &msg)
Definition: state_daemon.cpp:313
StateDaemon
Definition: state_daemon.h:45
StateDaemon::EdgeStatesCallback
void EdgeStatesCallback(const vda5050_msgs::EdgeStates::ConstPtr &msg)
Definition: state_daemon.cpp:222
ros::NodeHandle
Daemon::CheckTopic
bool CheckTopic(std::string str1, std::string str2)
Definition: src/daemon.cpp:117
StateDaemon::CheckPassedTime
bool CheckPassedTime()
Definition: state_daemon.cpp:40
StateDaemon::LastNodeIdCallback
void LastNodeIdCallback(const std_msgs::String::ConstPtr &msg)
Definition: state_daemon.cpp:210
ros::Time::now
static Time now()
StateDaemon::actionStatesSub
ros::Subscriber actionStatesSub
Definition: state_daemon.h:58


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