10 #ifndef ACTION_DAEMON_H 11 #define ACTION_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" 71 ActionElement(
const vda5050_msgs::Action *incomingAction,
string incomingOrderId,
string state);
81 bool compareActionId(
string actionId2comp);
91 bool compareOrderId(
string orderId2comp);
98 string getActionId()
const;
105 string getActionType()
const;
112 vda5050_msgs::Action packAction();
215 void OrderActionsCallback(
const vda5050_msgs::OrderActions::ConstPtr &msg);
225 void OrderTriggerCallback(
const std_msgs::String &msg);
237 void OrderCancelCallback(
const std_msgs::String &msg);
247 void InstantActionsCallback(
const vda5050_msgs::InstantActions::ConstPtr &msg);
258 void AgvActionStateCallback(
const vda5050_msgs::ActionState::ConstPtr &msg);
270 void DrivingCallback(
const std_msgs::Bool::ConstPtr &msg);
279 void AddActionToList(
const vda5050_msgs::Action *incomingAction,
string orderId,
string state);
294 vector<shared_ptr<ActionElement>> GetRunningActions();
301 vector<shared_ptr<ActionElement>> GetRunningPausedActions();
309 vector<shared_ptr<ActionElement>> GetActionsToCancel(
string orderIdToCancel);
319 shared_ptr<ActionElement> findAction(
string actionId);
327 void UpdateActions();
vector< weak_ptr< ActionElement > > actionsToCancel
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
vector< string > ordersSucCancelled
ros::Publisher allActionsCancelledPub
deque< vda5050_msgs::Action > orderActionQueue
deque< vda5050_msgs::Action > instantActionQueue
vector< orderToCancel > orderCancellations
bool allActionsCancelledSent
ros::Subscriber orderActionSub
ros::Subscriber orderTriggerSub
bool operator==(const ActionElement &s) const
vector< vda5050_msgs::ActionParameter > actionParameters
ros::Subscriber orderCancelSub