action_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 
10 #include <iostream>
11 #include <vector>
12 #include <string>
13 #include <list>
14 #include <memory>
15 #include "std_msgs/String.h"
16 #include "std_msgs/Bool.h"
18 #include "vda5050_msgs/ActionState.h"
19 #include "vda5050_msgs/Action.h"
20 #include "vda5050_msgs/OrderActions.h"
21 
22 using namespace std;
23 
32 /*--------------------------------ActionElement--------------------------------------------------------------*/
33 
34 ActionElement::ActionElement(const vda5050_msgs::Action *incomingAction, string incomingOrderId, string newState)
35 {
36  orderId = incomingOrderId;
37  actionId = incomingAction->actionId;
38  blockingType = incomingAction->blockingType;
39  actionType = incomingAction->actionType;
40  actionDescription = incomingAction->actionDescription;
41  actionParameters = incomingAction->actionParameters;
42  state = newState;
43 }
44 
45 bool ActionElement::compareActionId(string actionId2comp)
46 {
47  return actionId == actionId2comp;
48 }
49 
50 bool ActionElement::compareOrderId(string orderId2comp)
51 {
52  return orderId == orderId2comp;
53 }
54 
56 {
57  return actionId;
58 }
59 
61 {
62  return actionType;
63 }
64 
65 vda5050_msgs::Action ActionElement::packAction()
66 {
67  vda5050_msgs::Action msg;
68  msg.actionId = actionId;
69  msg.blockingType = blockingType;
70  msg.actionType = actionType;
71  msg.actionDescription = actionDescription;
72  msg.actionParameters = actionParameters;
73 
74  return msg;
75 }
76 
77 /*--------------------------------ActionDaemon--------------------------------------------------------------*/
78 
79 ActionDaemon::ActionDaemon() : Daemon(&(this->nh), "action_daemon")
80 {
81  LinkPublishTopics(&(this->nh));
82  LinkSubscriptionTopics(&(this->nh));
83 
85  orderActionSub = nh.subscribe("orderAction", 1000, &ActionDaemon::OrderActionsCallback, this);
86  orderTriggerSub = nh.subscribe("orderTrigger", 1000, &ActionDaemon::OrderTriggerCallback, this);
87  orderCancelSub = nh.subscribe("orderCancelResponse", 1000, &ActionDaemon::OrderCancelCallback, this);
88  actionStatesPub = nh.advertise<vda5050_msgs::ActionState>("actionStates", 1000);
89  orderCancelPub = nh.advertise<std_msgs::String>("orderCancelRequest", 1000);
90  allActionsCancelledPub = nh.advertise<std_msgs::String>("allActionsCancelled", 1000);
91 }
92 
94 {
95  map<string, string> topicList = GetTopicPublisherList();
96  std::string topic_index;
97 
98  for (const auto &elem : topicList)
99  {
100  topic_index = GetTopic(elem.first);
101  // ROS_INFO("topic_index = %s",topic_index.c_str());
102  if (CheckTopic(elem.first, "actionToAgv"))
103  messagePublisher[topic_index] = nh->advertise<vda5050_msgs::Action>(elem.second, 1000);
104  if (CheckTopic(elem.first, "agvActionCancel"))
105  messagePublisher[topic_index] = nh->advertise<std_msgs::String>(elem.second, 1000);
106  if (CheckTopic(elem.first, "prActions"))
107  messagePublisher[topic_index] = nh->advertise<std_msgs::String>(elem.second, 1000);
108  if (CheckTopic(elem.first, "prDriving"))
109  messagePublisher[topic_index] = nh->advertise<std_msgs::String>(elem.second, 1000);
110  }
111 }
112 
114 {
115  map<string, string> topicList = GetTopicSubscriberList();
116  for (const auto &elem : topicList)
117  {
118  if (CheckTopic(elem.first, "instantAction"))
119  subscribers[elem.first] = nh->subscribe(elem.second, 1000, &ActionDaemon::InstantActionsCallback, this);
120  if (CheckTopic(elem.first, "agvActionState"))
121  subscribers[elem.first] = nh->subscribe(elem.second, 1000, &ActionDaemon::AgvActionStateCallback, this);
122  if (CheckTopic(elem.first, "driving"))
123  subscribers[elem.first] = nh->subscribe(elem.second, 1000, &ActionDaemon::DrivingCallback, this);
124  }
125 }
126 
127 void ActionDaemon::OrderActionsCallback(const vda5050_msgs::OrderActions::ConstPtr &msg)
128 {
129  for (const auto &action : msg->orderActions)
130  {
132  string actionStatus = "WAITING";
133  ActionDaemon::AddActionToList(&action, msg->orderId, actionStatus);
134 
136  vda5050_msgs::ActionState state_msg;
137  state_msg.header = ActionDaemon::GetHeader();
138  state_msg.actionID = action.actionId;
139  state_msg.actionType = action.actionType;
140  state_msg.actionStatus = actionStatus;
141  state_msg.resultDescription = "";
142  actionStatesPub.publish(state_msg);
143  }
144 }
145 
146 void ActionDaemon::OrderTriggerCallback(const std_msgs::String &msg)
147 {
148  shared_ptr<ActionElement> activeAction = findAction(msg.data);
149 
150  // Sort out duplicates?#########################################################################debug
151 
152  if (activeAction)
153  {
155  vda5050_msgs::Action triggeredOrder = activeAction->packAction();
156  orderActionQueue.push_back(triggeredOrder);
157  ROS_INFO("Found Action to trigger: %s", msg.data.c_str());
158  }
159  else
160  ROS_WARN("Action to trigger not found!");
161 }
162 
163 void ActionDaemon::OrderCancelCallback(const std_msgs::String &msg)
164 {
165  ordersSucCancelled.push_back(msg.data);
166 }
167 
168 void ActionDaemon::InstantActionsCallback(const vda5050_msgs::InstantActions::ConstPtr &msg)
169 {
170  // Iterate over all actions in the instantActions msg
171  for (auto &iaction : msg->instantActions)
172  {
174  ActionDaemon::AddActionToList(&iaction, "Instant", "WAITING");
176  string orderIdToCancel;
177 
179  if (iaction.actionType == "cancelOrder")
180  {
182  vector<shared_ptr<ActionElement>> newActionsToCancel;
184  for (auto const &param : iaction.actionParameters)
185  {
186  if (param.key == "orderId")
187  {
188  orderIdToCancel = param.value;
189  newActionsToCancel = GetActionsToCancel(orderIdToCancel);
190  }
191  }
192 
194  for (std::vector<std::shared_ptr<ActionElement>>::iterator cAction = newActionsToCancel.begin();
195  cAction != newActionsToCancel.end();)
196  {
198  if (cAction->get()->state == "WAITING")
199  {
203  if (cAction->get()->sentToAgv)
204  {
206  std_msgs::String cancel_msg;
207  cancel_msg.data = string(cAction->get()->getActionId());
208  messagePublisher["agvActionCancel"].publish(cancel_msg);
209  cAction++;
210  }
211 
213  else
214  {
216  auto queueAction = find_if(orderActionQueue.begin(),
217  orderActionQueue.end(),
218  [cAction](vda5050_msgs::Action &orderAction)
219  { return orderAction.actionId ==
220  cAction->get()->getActionId(); });
222  if (queueAction != orderActionQueue.end())
223  orderActionQueue.erase(queueAction);
224 
226  newActionsToCancel.erase(
227  remove(newActionsToCancel.begin(),
228  newActionsToCancel.end(), *cAction));
229 
231  vda5050_msgs::ActionState state_msg;
232  state_msg.header = ActionDaemon::GetHeader();
233  state_msg.actionID = cAction->get()->getActionId();
234  state_msg.actionType = cAction->get()->getActionType();
235  state_msg.actionStatus = "FAILED";
236  state_msg.resultDescription = "order cancelled"; /*Description necessary?*/
237  actionStatesPub.publish(state_msg);
238 
240  auto actAct_it = find_if(
241  activeActionsList.begin(), activeActionsList.end(),
242  [cAction](shared_ptr<ActionElement> &activeAction)
243  { return cAction->get()->compareActionId(
244  cAction->get()->getActionId()); });
245 
246  if (actAct_it != activeActionsList.end())
247  {
248  activeActionsList.erase(actAct_it);
249  }
250  }
251  }
253  else
254  {
256  std_msgs::String cancel_msg;
257  cancel_msg.data = string(cAction->get()->getActionId());
258  messagePublisher["agvActionCancel"].publish(cancel_msg);
259  cAction++;
260  }
261  }
262 
264  orderToCancel newOrderToCancel;
265  newOrderToCancel.orderIdToCancel = orderIdToCancel;
266  newOrderToCancel.iActionId = iaction.actionId;
267  newOrderToCancel.allActionsCancelledSent = false;
268 
270  if (!newActionsToCancel.empty())
271  newOrderToCancel.actionsToCancel.insert(newOrderToCancel.actionsToCancel.end(), newActionsToCancel.begin(), newActionsToCancel.end());
276  orderCancellations.push_back(newOrderToCancel);
277 
279  std_msgs::String cancelOrderMsg;
280  cancelOrderMsg.data = orderIdToCancel;
281  orderCancelPub.publish(cancelOrderMsg);
282  }
283 
285  else
286  {
288  instantActionQueue.push_back(iaction);
290  vda5050_msgs::ActionState state_msg;
291  state_msg.header = ActionDaemon::GetHeader();
292  state_msg.actionID = iaction.actionId;
293  state_msg.actionType = iaction.actionType;
294  state_msg.actionStatus = "WAITING";
295  state_msg.resultDescription = "";
296  actionStatesPub.publish(state_msg);
297  }
298  }
299 }
300 
301 void ActionDaemon::AgvActionStateCallback(const vda5050_msgs::ActionState::ConstPtr &msg)
302 {
303  shared_ptr<ActionElement> actionToUpdate = findAction(msg->actionID);
305 
306  if (actionToUpdate)
307  {
308  actionStatesPub.publish(*msg);
309  if ((msg->actionStatus == "WAITING") || (msg->actionStatus == "INITIALIZING") || (msg->actionStatus == "RUNNING") || (msg->actionStatus == "PAUSED"))
310  {
311  actionToUpdate->state = msg->actionStatus;
312  // actionStatesPub.publish(msg);
313  }
314  else if (msg->actionStatus == "FINISHED")
315  {
316  if (actionToUpdate->blockingType != "NONE")
317  {
318  std_msgs::String resumeMsg;
319  resumeMsg.data = "RESUME";
320  messagePublisher["prDriving"].publish(resumeMsg);
321  }
322  // actionStatesPub.publish(msg);
323  activeActionsList.erase(remove(activeActionsList.begin(), activeActionsList.end(), actionToUpdate));
324  }
325  else if (msg->actionStatus == "FAILED")
326  {
327  if (actionToUpdate->blockingType != "NONE")
328  {
329  std_msgs::String resumeMsg;
330  resumeMsg.data = "RESUME";
331  messagePublisher["prDriving"].publish(resumeMsg);
332  }
333  // actionStatesPub.publish(msg);
334 
335  activeActionsList.erase(remove(activeActionsList.begin(), activeActionsList.end(), actionToUpdate));
336 
337  std_msgs::String cancelMsg;
338  cancelMsg.data = "CANCEL ORDER";
339  orderCancelPub.publish(cancelMsg);
340  }
341  }
342  else
343  ROS_WARN("Action to update not found!");
344 }
345 
346 void ActionDaemon::DrivingCallback(const std_msgs::Bool::ConstPtr &msg)
347 {
348  isDriving = msg->data;
349 }
350 
351 void ActionDaemon::AddActionToList(const vda5050_msgs::Action *incomingAction, string orderId, string state)
352 {
353  shared_ptr<ActionElement> newAction = make_shared<ActionElement>(incomingAction, orderId, state);
354  activeActionsList.push_back(newAction);
355 }
356 
358 {
359  if (isDriving)
360  {
361  std_msgs::String pauseMsg;
362  pauseMsg.data = "PAUSE";
363  messagePublisher["prDriving"].publish(pauseMsg);
364  return false;
365  }
366  else
367  return true;
368 }
369 
370 vector<shared_ptr<ActionElement>> ActionDaemon::GetRunningActions()
371 {
372  vector<shared_ptr<ActionElement>> runningActions;
373  for (auto const &action_it : activeActionsList)
374  {
375  if (action_it->state == "RUNNING")
376  {
377  runningActions.push_back(action_it);
378  }
379  }
380  return runningActions;
381 }
382 
383 vector<shared_ptr<ActionElement>> ActionDaemon::GetRunningPausedActions()
384 {
385  vector<shared_ptr<ActionElement>> runningPausedActions;
386  for (auto const &action_it : activeActionsList)
387  {
388  if (action_it->state == "RUNNING" || action_it->state == "PAUSED")
389  {
390  runningPausedActions.push_back(action_it);
391  }
392  }
393  return runningPausedActions;
394 }
395 
396 vector<shared_ptr<ActionElement>> ActionDaemon::GetActionsToCancel(string orderIdToCancel)
397 {
398  vector<shared_ptr<ActionElement>> actionsToCancel;
399  auto it = activeActionsList.begin();
400  while ((it = find_if(it, activeActionsList.end(), [&orderIdToCancel](shared_ptr<ActionElement> const &p)
401  { return p->compareOrderId(orderIdToCancel); })) != activeActionsList.end())
402  {
403  actionsToCancel.push_back(*it);
404  it++;
405  }
406 
407  return actionsToCancel;
408 }
409 
410 shared_ptr<ActionElement> ActionDaemon::findAction(string actionId)
411 {
412  vector<shared_ptr<ActionElement>>::iterator it = find_if(activeActionsList.begin(), activeActionsList.end(),
413  [&actionId](shared_ptr<ActionElement> const &p)
414  { return p->compareActionId(actionId); });
415  if (it == activeActionsList.end())
416  return nullptr;
417  else
418  return *it;
419 }
420 
422 {
424  if (!orderCancellations.empty())
425  {
426  vector<orderToCancel> orderCancellationsFinished;
427  for (auto &orderCan_it : orderCancellations)
428  {
431  if (!orderCan_it.actionsToCancel.empty())
432  {
433  orderCan_it.actionsToCancel.erase(
434  remove_if(
435  orderCan_it.actionsToCancel.begin(),
436  orderCan_it.actionsToCancel.end(),
437  [&](weak_ptr<ActionElement> const &p)
438  { return p.expired(); }),
439  orderCan_it.actionsToCancel.end());
440  }
443  if (orderCan_it.actionsToCancel.empty())
444  {
446  if (!orderCan_it.allActionsCancelledSent)
447  {
448  std_msgs::String allActionsCancelledMsg;
449  allActionsCancelledMsg.data = orderCan_it.orderIdToCancel;
450  allActionsCancelledPub.publish(allActionsCancelledMsg);
451  }
452 
454  auto orderCancelled = find_if(ordersSucCancelled.begin(), ordersSucCancelled.end(),
455  [orderCan_it](string orderCanc)
456  { return orderCan_it.orderIdToCancel == orderCanc; });
458  if (orderCancelled != ordersSucCancelled.end())
459  {
461  auto actAct_it = find_if(activeActionsList.begin(), activeActionsList.end(),
462  [&orderCan_it](shared_ptr<ActionElement> &activeAction)
463  { return activeAction->compareActionId(orderCan_it.iActionId); });
464  if (actAct_it != activeActionsList.end())
465  {
467  vda5050_msgs::ActionState state_msg;
468  state_msg.header = ActionDaemon::GetHeader();
469  state_msg.actionID = (**actAct_it).getActionId();
470  state_msg.actionType = (**actAct_it).getActionType();
471  state_msg.actionStatus = "FINISHED";
472  state_msg.resultDescription = ""; /*Description necessary?*/
473  actionStatesPub.publish(state_msg);
474 
476  activeActionsList.erase(actAct_it);
477  }
478  else
479  {
480  ROS_ERROR_STREAM("ACTION NOT FOUND IN ACTIVE ACTIONS!");
481  }
482 
484  ordersSucCancelled.erase(orderCancelled);
486  orderCancellationsFinished.push_back(orderCan_it);
487  }
488  }
489  }
491  for (auto const &finishedOrderCancel : orderCancellationsFinished)
492  {
493  auto ordCan_it = find_if(orderCancellations.begin(), orderCancellations.end(),
494  [&finishedOrderCancel](orderToCancel &orderCancel)
495  { return orderCancel.iActionId == finishedOrderCancel.iActionId; });
496  if (ordCan_it != orderCancellations.end())
497  orderCancellations.erase(ordCan_it);
498  }
499  }
500 
502  else if (!instantActionQueue.empty())
503  {
505  vector<shared_ptr<ActionElement>> runningPausedActions = GetRunningPausedActions();
506 
507  if (!runningPausedActions.empty())
508  {
510  bool RunningActionHardBlocking = false;
511  for (auto &elem : runningPausedActions)
512  {
513  if (elem->state == "RUNNING" && elem->blockingType == "HARD")
514  RunningActionHardBlocking = true;
515  }
516  if (!RunningActionHardBlocking)
517  {
519  string &nextBlockType = instantActionQueue.front().blockingType;
520 
521  if (nextBlockType == "HARD")
522  {
523  if (checkDriving())
524  {
526  auto sentAction = findAction(instantActionQueue.front().actionId);
527  sentAction->sentToAgv = true;
528 
530  vda5050_msgs::Action instantActionMsg = instantActionQueue.front();
531  messagePublisher["actionToAgv"].publish(instantActionMsg);
532  instantActionQueue.pop_front();
533  }
535  std_msgs::String pause_msg;
536  pause_msg.data = "PAUSE";
537  messagePublisher["prActions"].publish(pause_msg);
538  }
539  else if (nextBlockType == "SOFT")
540  {
541  if (checkDriving())
542  {
544  auto sentAction = findAction(instantActionQueue.front().actionId);
545  sentAction->sentToAgv = true;
546 
548  vda5050_msgs::Action instantActionMsg = instantActionQueue.front();
549  messagePublisher["actionToAgv"].publish(instantActionMsg);
550  instantActionQueue.pop_front();
551  }
552  }
553  else if (nextBlockType == "NONE")
554  {
556  auto sentAction = findAction(instantActionQueue.front().actionId);
557  sentAction->sentToAgv = true;
558 
560  vda5050_msgs::Action instantActionMsg = instantActionQueue.front();
561  messagePublisher["actionToAgv"].publish(instantActionMsg);
562 
563  instantActionQueue.pop_front();
564  }
565  }
566  else
567  {
569  std_msgs::String pause_msg;
570  pause_msg.data = "PAUSE";
571  messagePublisher["prActions"].publish(pause_msg);
572  }
573  }
574 
576  else
577  {
579  auto sentAction = findAction(instantActionQueue.front().actionId);
580  sentAction->sentToAgv = true;
581 
583  vda5050_msgs::Action instantActionMsg = instantActionQueue.front();
584  messagePublisher["actionToAgv"].publish(instantActionMsg);
585  instantActionQueue.pop_front();
586  }
587  }
588 
590  else if (!orderActionQueue.empty())
591  {
593  vector<shared_ptr<ActionElement>> runningPausedActions = GetRunningPausedActions();
594 
595  if (!runningPausedActions.empty())
596  {
598  bool RunningActionHardBlocking = false;
599  for (auto &elem : runningPausedActions)
600  {
601  if (elem->state == "RUNNING" && elem->blockingType == "HARD")
602  RunningActionHardBlocking = true;
603  }
604 
605  if (!RunningActionHardBlocking)
606  {
607  for (auto const &action_it : runningPausedActions)
608  {
610  if (action_it->state == "PAUSED")
611  {
612  std_msgs::String resume_msg;
613  resume_msg.data = "RESUME";
614  messagePublisher["prActions"].publish(resume_msg);
615  }
617  else
618  {
620  string &nextBlockType = orderActionQueue.front().blockingType;
621  if (nextBlockType == "HARD")
622  {
626  {
628  auto sentAction = findAction(orderActionQueue.front().actionId);
629  sentAction->sentToAgv = true;
630 
632  vda5050_msgs::Action orderActionMsg = orderActionQueue.front();
633  messagePublisher["actionToAgv"].publish(orderActionMsg);
634  orderActionQueue.pop_front();
635  }
636  }
638  else if (nextBlockType == "SOFT")
639  {
641  if (checkDriving())
642  {
644  auto sentAction = findAction(orderActionQueue.front().actionId);
645  sentAction->sentToAgv = true;
646 
648  vda5050_msgs::Action orderActionMsg = orderActionQueue.front();
649  messagePublisher["actionToAgv"].publish(orderActionMsg);
650  orderActionQueue.pop_front();
651  }
652  }
654  else if (nextBlockType == "NONE")
655  {
657  auto sentAction = findAction(orderActionQueue.front().actionId);
658  sentAction->sentToAgv = true;
659 
661  vda5050_msgs::Action orderActionMsg = orderActionQueue.front();
662  messagePublisher["actionToAgv"].publish(orderActionMsg);
663  orderActionQueue.pop_front();
664  }
665  }
666  }
667  }
668  }
669 
671  else
672  {
674  auto sentAction = findAction(orderActionQueue.front().actionId);
675  sentAction->sentToAgv = true;
676 
678  vda5050_msgs::Action orderActionMsg = orderActionQueue.front();
679  messagePublisher["actionToAgv"].publish(orderActionMsg);
680  orderActionQueue.pop_front();
681  }
682  }
683 }
684 
685 int main(int argc, char **argv)
686 {
687  ros::init(argc, argv, "action_deamon");
688 
689  ActionDaemon actionDaemon;
690 
691  while (ros::ok())
692  {
693  actionDaemon.UpdateActions();
694  ros::spinOnce();
695  }
696  return 0;
697 }
orderToCancel::actionsToCancel
vector< weak_ptr< ActionElement > > actionsToCancel
Definition: action_daemon.h:126
ActionDaemon::orderCancelSub
ros::Subscriber orderCancelSub
Definition: action_daemon.h:158
ActionDaemon::ordersSucCancelled
vector< string > ordersSucCancelled
Definition: action_daemon.h:183
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
ActionDaemon::OrderCancelCallback
void OrderCancelCallback(const std_msgs::String &msg)
Definition: action_daemon.cpp:163
ActionElement::packAction
vda5050_msgs::Action packAction()
Definition: action_daemon.cpp:65
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ActionDaemon::isDriving
bool isDriving
Definition: action_daemon.h:172
ActionDaemon::instantActionQueue
deque< vda5050_msgs::Action > instantActionQueue
Definition: action_daemon.h:180
ActionElement::compareOrderId
bool compareOrderId(string orderId2comp)
Definition: action_daemon.cpp:50
Daemon::subscribers
std::map< std::string, ros::Subscriber > subscribers
Definition: daemon.h:59
ros::spinOnce
ROSCPP_DECL void spinOnce()
ActionDaemon::orderTriggerSub
ros::Subscriber orderTriggerSub
Definition: action_daemon.h:155
orderToCancel::allActionsCancelledSent
bool allActionsCancelledSent
Definition: action_daemon.h:129
ActionDaemon::allActionsCancelledPub
ros::Publisher allActionsCancelledPub
Definition: action_daemon.h:167
ActionDaemon::findAction
shared_ptr< ActionElement > findAction(string actionId)
Definition: action_daemon.cpp:410
ActionElement::getActionId
string getActionId() const
Definition: action_daemon.cpp:55
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
ActionDaemon::AgvActionStateCallback
void AgvActionStateCallback(const vda5050_msgs::ActionState::ConstPtr &msg)
Definition: action_daemon.cpp:301
ActionElement::compareActionId
bool compareActionId(string actionId2comp)
Definition: action_daemon.cpp:45
ActionDaemon::activeActionsList
vector< shared_ptr< ActionElement > > activeActionsList
Definition: action_daemon.h:140
ActionDaemon::GetRunningActions
vector< shared_ptr< ActionElement > > GetRunningActions()
Definition: action_daemon.cpp:370
Daemon::GetTopicSubscriberList
std::map< std::string, std::string > GetTopicSubscriberList()
Definition: src/daemon.cpp:51
orderToCancel
Definition: action_daemon.h:118
Daemon::GetTopic
std::string GetTopic(std::string hierarchical_topic)
Definition: src/daemon.cpp:128
ActionDaemon::UpdateActions
void UpdateActions()
Definition: action_daemon.cpp:421
ActionDaemon::LinkSubscriptionTopics
void LinkSubscriptionTopics(ros::NodeHandle *nh)
Definition: action_daemon.cpp:113
Daemon::messagePublisher
std::map< std::string, ros::Publisher > messagePublisher
Definition: daemon.h:54
ActionDaemon::orderActionSub
ros::Subscriber orderActionSub
Definition: action_daemon.h:152
ActionDaemon::checkDriving
bool checkDriving()
Definition: action_daemon.cpp:357
orderToCancel::iActionId
string iActionId
Definition: action_daemon.h:123
ActionElement::ActionElement
ActionElement(const vda5050_msgs::Action *incomingAction, string incomingOrderId, string state)
Definition: action_daemon.cpp:34
ROS_WARN
#define ROS_WARN(...)
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())
ActionDaemon::ActionDaemon
ActionDaemon()
Definition: action_daemon.cpp:79
Daemon::nh
ros::NodeHandle nh
Definition: daemon.h:67
Daemon
Definition: daemon.h:29
ActionDaemon::LinkPublishTopics
void LinkPublishTopics(ros::NodeHandle *nh)
Definition: action_daemon.cpp:93
orderToCancel::orderIdToCancel
string orderIdToCancel
Definition: action_daemon.h:120
ActionDaemon::InstantActionsCallback
void InstantActionsCallback(const vda5050_msgs::InstantActions::ConstPtr &msg)
Definition: action_daemon.cpp:168
main
int main(int argc, char **argv)
Definition: action_daemon.cpp:685
ActionDaemon::orderActionQueue
deque< vda5050_msgs::Action > orderActionQueue
Definition: action_daemon.h:177
std
ActionDaemon::GetActionsToCancel
vector< shared_ptr< ActionElement > > GetActionsToCancel(string orderIdToCancel)
Definition: action_daemon.cpp:396
ActionDaemon::actionStatesPub
ros::Publisher actionStatesPub
Definition: action_daemon.h:161
param
T param(const std::string &param_name, const T &default_val)
ActionDaemon::orderCancellations
vector< orderToCancel > orderCancellations
Definition: action_daemon.h:143
ActionDaemon::orderCancelPub
ros::Publisher orderCancelPub
Definition: action_daemon.h:164
ActionDaemon::OrderTriggerCallback
void OrderTriggerCallback(const std_msgs::String &msg)
Definition: action_daemon.cpp:146
action_daemon.h
ROS_INFO
#define ROS_INFO(...)
ActionDaemon::GetRunningPausedActions
vector< shared_ptr< ActionElement > > GetRunningPausedActions()
Definition: action_daemon.cpp:383
ActionElement::getActionType
string getActionType() const
Definition: action_daemon.cpp:60
ActionDaemon::OrderActionsCallback
void OrderActionsCallback(const vda5050_msgs::OrderActions::ConstPtr &msg)
Definition: action_daemon.cpp:127
ActionDaemon::DrivingCallback
void DrivingCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: action_daemon.cpp:346
ros::NodeHandle
Daemon::CheckTopic
bool CheckTopic(std::string str1, std::string str2)
Definition: src/daemon.cpp:117
ActionDaemon
Definition: action_daemon.h:137
ActionDaemon::AddActionToList
void AddActionToList(const vda5050_msgs::Action *incomingAction, string orderId, string state)
Definition: action_daemon.cpp:351


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