action_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 ACTION_DAEMON_H
11 #define ACTION_DAEMON_H
12 #include <string>
13 #include <list>
14 #include <deque>
15 #include <memory>
16 #include <ros/ros.h>
17 #include "daemon.h"
18 #include "vda5050_msgs/InstantActions.h"
19 #include "vda5050_msgs/ActionState.h"
20 #include "vda5050_msgs/OrderActions.h"
21 #include "std_msgs/Bool.h"
22 #include <string>
23 #include <list>
24 #include <deque>
25 #include <memory>
26 
27 using namespace std;
28 
33 {
34 private:
35  string orderId;
38  string actionId;
41  string actionType;
47  vector<vda5050_msgs::ActionParameter> actionParameters;
51 public:
52  string state;
55  string blockingType;
58  bool sentToAgv;
61  bool operator==(const ActionElement &s) const { return actionId == s.actionId; }
62  bool operator!=(const ActionElement &s) const { return !operator==(s); }
63 
71  ActionElement(const vda5050_msgs::Action *incomingAction, string incomingOrderId, string state);
72 
81  bool compareActionId(string actionId2comp);
82 
91  bool compareOrderId(string orderId2comp);
92 
98  string getActionId() const;
99 
105  string getActionType() const;
106 
112  vda5050_msgs::Action packAction();
113 };
114 
119 {
123  string iActionId;
126  vector<weak_ptr<ActionElement>> actionsToCancel;
132 };
133 
137 class ActionDaemon : public Daemon
138 {
139 private:
140  vector<shared_ptr<ActionElement>> activeActionsList;
143  vector<orderToCancel> orderCancellations;
172  bool isDriving;
176 protected:
177  deque<vda5050_msgs::Action> orderActionQueue;
180  deque<vda5050_msgs::Action> instantActionQueue;
183  vector<string> ordersSucCancelled;
187 public:
191  ActionDaemon();
192 
198  void LinkPublishTopics(ros::NodeHandle *nh);
199 
205  void LinkSubscriptionTopics(ros::NodeHandle *nh);
206 
215  void OrderActionsCallback(const vda5050_msgs::OrderActions::ConstPtr &msg);
216 
225  void OrderTriggerCallback(const std_msgs::String &msg);
226 
237  void OrderCancelCallback(const std_msgs::String &msg);
238 
247  void InstantActionsCallback(const vda5050_msgs::InstantActions::ConstPtr &msg);
248 
258  void AgvActionStateCallback(const vda5050_msgs::ActionState::ConstPtr &msg);
259 
270  void DrivingCallback(const std_msgs::Bool::ConstPtr &msg);
271 
279  void AddActionToList(const vda5050_msgs::Action *incomingAction, string orderId, string state);
280 
287  bool checkDriving();
288 
294  vector<shared_ptr<ActionElement>> GetRunningActions();
295 
301  vector<shared_ptr<ActionElement>> GetRunningPausedActions();
302 
309  vector<shared_ptr<ActionElement>> GetActionsToCancel(string orderIdToCancel);
310 
319  shared_ptr<ActionElement> findAction(string actionId);
320 
327  void UpdateActions();
328 };
329 
330 #endif
string blockingType
Definition: action_daemon.h:55
vector< weak_ptr< ActionElement > > actionsToCancel
string actionType
Definition: action_daemon.h:41
vector< shared_ptr< ActionElement > > activeActionsList
bool operator==(const in6_addr a, const in6_addr b)
ros::Publisher orderCancelPub
ros::Publisher actionStatesPub
bool operator!=(const ActionElement &s) const
Definition: action_daemon.h:62
string orderIdToCancel
vector< string > ordersSucCancelled
ros::Publisher allActionsCancelledPub
deque< vda5050_msgs::Action > orderActionQueue
deque< vda5050_msgs::Action > instantActionQueue
vector< orderToCancel > orderCancellations
bool allActionsCancelledSent
ros::Subscriber orderActionSub
Definition: daemon.h:29
ros::Subscriber orderTriggerSub
bool operator==(const ActionElement &s) const
Definition: action_daemon.h:61
vector< vda5050_msgs::ActionParameter > actionParameters
Definition: action_daemon.h:47
ros::Subscriber orderCancelSub
string actionDescription
Definition: action_daemon.h:44


vda5050_connector
Author(s): Florian Rothmeyer , Florian Spiegel
autogenerated on Tue Mar 21 2023 02:52:00