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
orderToCancel::actionsToCancel
vector< weak_ptr< ActionElement > > actionsToCancel
Definition: action_daemon.h:126
ActionDaemon::orderCancelSub
ros::Subscriber orderCancelSub
Definition: action_daemon.h:158
ActionElement::operator==
bool operator==(const ActionElement &s) const
Definition: action_daemon.h:61
ActionDaemon::ordersSucCancelled
vector< string > ordersSucCancelled
Definition: action_daemon.h:183
ros::Publisher
ActionElement::actionId
string actionId
Definition: action_daemon.h:38
ActionElement::operator!=
bool operator!=(const ActionElement &s) const
Definition: action_daemon.h:62
ActionDaemon::isDriving
bool isDriving
Definition: action_daemon.h:172
s
XmlRpcServer s
ActionElement::actionParameters
vector< vda5050_msgs::ActionParameter > actionParameters
Definition: action_daemon.h:47
ros.h
ActionDaemon::instantActionQueue
deque< vda5050_msgs::Action > instantActionQueue
Definition: action_daemon.h:180
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
ActionElement::state
string state
Definition: action_daemon.h:52
ActionDaemon::activeActionsList
vector< shared_ptr< ActionElement > > activeActionsList
Definition: action_daemon.h:140
ActionElement
Definition: action_daemon.h:32
ActionElement::actionDescription
string actionDescription
Definition: action_daemon.h:44
ActionElement::actionType
string actionType
Definition: action_daemon.h:41
orderToCancel
Definition: action_daemon.h:118
operator==
bool operator==(const in6_addr a, const in6_addr b)
ActionElement::orderId
string orderId
Definition: action_daemon.h:35
ActionDaemon::orderActionSub
ros::Subscriber orderActionSub
Definition: action_daemon.h:152
orderToCancel::iActionId
string iActionId
Definition: action_daemon.h:123
Daemon
Definition: daemon.h:29
ActionElement::blockingType
string blockingType
Definition: action_daemon.h:55
orderToCancel::orderIdToCancel
string orderIdToCancel
Definition: action_daemon.h:120
ActionDaemon::orderActionQueue
deque< vda5050_msgs::Action > orderActionQueue
Definition: action_daemon.h:177
ActionElement::sentToAgv
bool sentToAgv
Definition: action_daemon.h:58
std
ActionDaemon::actionStatesPub
ros::Publisher actionStatesPub
Definition: action_daemon.h:161
ActionDaemon::orderCancellations
vector< orderToCancel > orderCancellations
Definition: action_daemon.h:143
ActionDaemon::orderCancelPub
ros::Publisher orderCancelPub
Definition: action_daemon.h:164
ros::NodeHandle
ros::Subscriber
ActionDaemon
Definition: action_daemon.h:137
daemon.h


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