#include <order_daemon.h>
Public Member Functions | |
| bool | compareBase (string startOfNewBaseNodeId, int startOfNewBaseSequenceId) |
| bool | compareOrderId (string orderIdToCompare) |
| string | compareOrderUpdateId (int orderUpdateIdToCompare) |
| CurrentOrder (const vda5050_msgs::Order::ConstPtr &incomingOrder) | |
| string | findNodeEdge (int currSequenceId) |
| vda5050_msgs::Node | getLastNodeInBase () |
| string | getOrderId () |
| int | getOrderUpdateId () |
| bool | isActive () |
| void | sendActions (ros::Publisher actionPublisher) |
| void | sendEdgeStates (ros::Publisher edgeStatesPublisher) |
| void | sendNodeStates (ros::Publisher nodeStatesPublisher) |
| void | setOrderUpdateId (int incomingUpdateId) |
Public Attributes | |
| bool | actionCancellationComplete |
| bool | actionsFinished |
| vector< string > | actionStates |
| deque< vda5050_msgs::Edge > | edgeStates |
| deque< vda5050_msgs::Node > | nodeStates |
Private Attributes | |
| string | orderId |
| int | orderUpdateId |
| string | zoneSetId |
Daemon for processing of VDA 5050 action messages. The order daemon consists of a) a main loop which processes orders according to their states and changes in the system state and b) several callbacks which receive and process system changes.
Definition at line 31 of file order_daemon.h.
| CurrentOrder::CurrentOrder | ( | const vda5050_msgs::Order::ConstPtr & | incomingOrder | ) |
Constructor for a CurrentOrder object.
| incomingOrder | Pointer to the order message. |
Definition at line 30 of file order_daemon.cpp.
| bool CurrentOrder::compareBase | ( | string | startOfNewBaseNodeId, |
| int | startOfNewBaseSequenceId | ||
| ) |
Compares start of new base and end of current base.
| startOfNewBaseNodeId | Start of new base node ID. |
| startOfNewBaseSequenceId | Start of new base sequence ID. |
Definition at line 59 of file order_daemon.cpp.
| bool CurrentOrder::compareOrderId | ( | string | orderIdToCompare | ) |
Check if the given OrderID belongs to the current order.
| orderIdToCompare | OrderID string that should be compared against |
Definition at line 42 of file order_daemon.cpp.
| string CurrentOrder::compareOrderUpdateId | ( | int | orderUpdateIdToCompare | ) |
Compares the incoming order update ID with the currently running order update ID.
| orderUpdateIdToCompare | The order update ID of the incoming order. |
Definition at line 47 of file order_daemon.cpp.
| string CurrentOrder::findNodeEdge | ( | int | currSequenceId | ) |
Returns "NODE" or "EDGE" based on the sequence ID.
| currSequenceId | Current sequence ID. |
Definition at line 93 of file order_daemon.cpp.
| vda5050_msgs::Node CurrentOrder::getLastNodeInBase | ( | ) |
Get the last released node. The last released node means the last node in current base.
find first element which is not released to find end of base
if an element in the horizon is found -> return the element before (== last element in base)
if the horizon is empty, take the last element of the list (== last element in base)
Definition at line 103 of file order_daemon.cpp.
| string CurrentOrder::getOrderId | ( | ) |
| int CurrentOrder::getOrderUpdateId | ( | ) |
Get the order update ID.
Definition at line 70 of file order_daemon.cpp.
| bool CurrentOrder::isActive | ( | ) |
Tells us whether or not the order is active.
Definition at line 80 of file order_daemon.cpp.
| void CurrentOrder::sendActions | ( | ros::Publisher | actionPublisher | ) |
Sends all new actions to action daemon
| actionPublisher | ROS publisher to use for sending the actions. |
in case the first node has no actions, set actions finished to true
TODO: Offene Frage: startet sequenceId bei 0?
Definition at line 115 of file order_daemon.cpp.
| void CurrentOrder::sendEdgeStates | ( | ros::Publisher | edgeStatesPublisher | ) |
Sends all new edge states to state daemon.
| edgeStatesPublisher | ROS publisher to use for sending the edge states. |
Create node states message
publish node states message
Definition at line 165 of file order_daemon.cpp.
| void CurrentOrder::sendNodeStates | ( | ros::Publisher | nodeStatesPublisher | ) |
Sends all new node states to state daemon.
| nodeStatesPublisher | ROS publisher to use for sending the node states. |
Create node states message
publish node states message
Definition at line 146 of file order_daemon.cpp.
| void CurrentOrder::setOrderUpdateId | ( | int | incomingUpdateId | ) |
Set the Order Update Id object.
| incomingUpdateId | Incoming order update ID. |
Definition at line 75 of file order_daemon.cpp.
| bool CurrentOrder::actionCancellationComplete |
All actions cancelled in case of order cancellation.
Definition at line 48 of file order_daemon.h.
| bool CurrentOrder::actionsFinished |
All actions related to current edge or node finished?
Definition at line 45 of file order_daemon.h.
| vector<string> CurrentOrder::actionStates |
Vector containing the states of all active actions.
Definition at line 57 of file order_daemon.h.
| deque<vda5050_msgs::Edge> CurrentOrder::edgeStates |
Contains all edges which the AGV has not completed yet.
Definition at line 51 of file order_daemon.h.
| deque<vda5050_msgs::Node> CurrentOrder::nodeStates |
Contains all nodes which the AGV has not completed yet.
Definition at line 54 of file order_daemon.h.
|
private |
Order ID of the order object.
Definition at line 34 of file order_daemon.h.
|
private |
Current Order update ID of the order object.
Definition at line 37 of file order_daemon.h.
|
private |
ZoneSetID of the order object.
Definition at line 40 of file order_daemon.h.