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"
36 orderId = incomingOrderId;
37 actionId = incomingAction->actionId;
38 blockingType = incomingAction->blockingType;
39 actionType = incomingAction->actionType;
40 actionDescription = incomingAction->actionDescription;
41 actionParameters = incomingAction->actionParameters;
47 return actionId == actionId2comp;
52 return orderId == orderId2comp;
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;
96 std::string topic_index;
98 for (
const auto &elem : topicList)
104 if (
CheckTopic(elem.first,
"agvActionCancel"))
116 for (
const auto &elem : topicList)
129 for (
const auto &action : msg->orderActions)
132 string actionStatus =
"WAITING";
136 vda5050_msgs::ActionState state_msg;
138 state_msg.actionID = action.actionId;
139 state_msg.actionType = action.actionType;
140 state_msg.actionStatus = actionStatus;
141 state_msg.resultDescription =
"";
148 shared_ptr<ActionElement> activeAction =
findAction(msg.data);
155 vda5050_msgs::Action triggeredOrder = activeAction->packAction();
157 ROS_INFO(
"Found Action to trigger: %s", msg.data.c_str());
160 ROS_WARN(
"Action to trigger not found!");
171 for (
auto &iaction : msg->instantActions)
176 string orderIdToCancel;
179 if (iaction.actionType ==
"cancelOrder")
182 vector<shared_ptr<ActionElement>> newActionsToCancel;
184 for (
auto const &
param : iaction.actionParameters)
186 if (
param.key ==
"orderId")
188 orderIdToCancel =
param.value;
194 for (std::vector<std::shared_ptr<ActionElement>>::iterator cAction = newActionsToCancel.begin();
195 cAction != newActionsToCancel.end();)
198 if (cAction->get()->state ==
"WAITING")
203 if (cAction->get()->sentToAgv)
206 std_msgs::String cancel_msg;
207 cancel_msg.data = string(cAction->get()->getActionId());
218 [cAction](vda5050_msgs::Action &orderAction)
219 { return orderAction.actionId ==
220 cAction->get()->getActionId(); });
226 newActionsToCancel.erase(
227 remove(newActionsToCancel.begin(),
228 newActionsToCancel.end(), *cAction));
231 vda5050_msgs::ActionState state_msg;
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";
240 auto actAct_it = find_if(
242 [cAction](shared_ptr<ActionElement> &activeAction)
243 { return cAction->get()->compareActionId(
244 cAction->get()->getActionId()); });
256 std_msgs::String cancel_msg;
257 cancel_msg.data = string(cAction->get()->getActionId());
266 newOrderToCancel.
iActionId = iaction.actionId;
270 if (!newActionsToCancel.empty())
279 std_msgs::String cancelOrderMsg;
280 cancelOrderMsg.data = orderIdToCancel;
290 vda5050_msgs::ActionState state_msg;
292 state_msg.actionID = iaction.actionId;
293 state_msg.actionType = iaction.actionType;
294 state_msg.actionStatus =
"WAITING";
295 state_msg.resultDescription =
"";
303 shared_ptr<ActionElement> actionToUpdate =
findAction(msg->actionID);
309 if ((msg->actionStatus ==
"WAITING") || (msg->actionStatus ==
"INITIALIZING") || (msg->actionStatus ==
"RUNNING") || (msg->actionStatus ==
"PAUSED"))
311 actionToUpdate->state = msg->actionStatus;
314 else if (msg->actionStatus ==
"FINISHED")
316 if (actionToUpdate->blockingType !=
"NONE")
318 std_msgs::String resumeMsg;
319 resumeMsg.data =
"RESUME";
325 else if (msg->actionStatus ==
"FAILED")
327 if (actionToUpdate->blockingType !=
"NONE")
329 std_msgs::String resumeMsg;
330 resumeMsg.data =
"RESUME";
337 std_msgs::String cancelMsg;
338 cancelMsg.data =
"CANCEL ORDER";
343 ROS_WARN(
"Action to update not found!");
353 shared_ptr<ActionElement> newAction = make_shared<ActionElement>(incomingAction, orderId, state);
361 std_msgs::String pauseMsg;
362 pauseMsg.data =
"PAUSE";
372 vector<shared_ptr<ActionElement>> runningActions;
375 if (action_it->state ==
"RUNNING")
377 runningActions.push_back(action_it);
380 return runningActions;
385 vector<shared_ptr<ActionElement>> runningPausedActions;
388 if (action_it->state ==
"RUNNING" || action_it->state ==
"PAUSED")
390 runningPausedActions.push_back(action_it);
393 return runningPausedActions;
398 vector<shared_ptr<ActionElement>> actionsToCancel;
400 while ((it = find_if(it,
activeActionsList.end(), [&orderIdToCancel](shared_ptr<ActionElement>
const &p)
403 actionsToCancel.push_back(*it);
407 return actionsToCancel;
413 [&actionId](shared_ptr<ActionElement>
const &p)
414 { return p->compareActionId(actionId); });
426 vector<orderToCancel> orderCancellationsFinished;
431 if (!orderCan_it.actionsToCancel.empty())
433 orderCan_it.actionsToCancel.erase(
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());
443 if (orderCan_it.actionsToCancel.empty())
446 if (!orderCan_it.allActionsCancelledSent)
448 std_msgs::String allActionsCancelledMsg;
449 allActionsCancelledMsg.data = orderCan_it.orderIdToCancel;
455 [orderCan_it](
string orderCanc)
456 { return orderCan_it.orderIdToCancel == orderCanc; });
462 [&orderCan_it](shared_ptr<ActionElement> &activeAction)
463 { return activeAction->compareActionId(orderCan_it.iActionId); });
467 vda5050_msgs::ActionState state_msg;
469 state_msg.actionID = (**actAct_it).getActionId();
470 state_msg.actionType = (**actAct_it).getActionType();
471 state_msg.actionStatus =
"FINISHED";
472 state_msg.resultDescription =
"";
486 orderCancellationsFinished.push_back(orderCan_it);
491 for (
auto const &finishedOrderCancel : orderCancellationsFinished)
495 { return orderCancel.iActionId == finishedOrderCancel.iActionId; });
507 if (!runningPausedActions.empty())
510 bool RunningActionHardBlocking =
false;
511 for (
auto &elem : runningPausedActions)
513 if (elem->state ==
"RUNNING" && elem->blockingType ==
"HARD")
514 RunningActionHardBlocking =
true;
516 if (!RunningActionHardBlocking)
521 if (nextBlockType ==
"HARD")
527 sentAction->sentToAgv =
true;
535 std_msgs::String pause_msg;
536 pause_msg.data =
"PAUSE";
539 else if (nextBlockType ==
"SOFT")
545 sentAction->sentToAgv =
true;
553 else if (nextBlockType ==
"NONE")
557 sentAction->sentToAgv =
true;
569 std_msgs::String pause_msg;
570 pause_msg.data =
"PAUSE";
580 sentAction->sentToAgv =
true;
595 if (!runningPausedActions.empty())
598 bool RunningActionHardBlocking =
false;
599 for (
auto &elem : runningPausedActions)
601 if (elem->state ==
"RUNNING" && elem->blockingType ==
"HARD")
602 RunningActionHardBlocking =
true;
605 if (!RunningActionHardBlocking)
607 for (
auto const &action_it : runningPausedActions)
610 if (action_it->state ==
"PAUSED")
612 std_msgs::String resume_msg;
613 resume_msg.data =
"RESUME";
621 if (nextBlockType ==
"HARD")
629 sentAction->sentToAgv =
true;
638 else if (nextBlockType ==
"SOFT")
645 sentAction->sentToAgv =
true;
654 else if (nextBlockType ==
"NONE")
658 sentAction->sentToAgv =
true;
675 sentAction->sentToAgv =
true;
685 int main(
int argc,
char **argv)