Public Member Functions | Public Attributes | Private Attributes | List of all members
CurrentOrder Class Reference

#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
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ CurrentOrder()

CurrentOrder::CurrentOrder ( const vda5050_msgs::Order::ConstPtr &  incomingOrder)

Constructor for a CurrentOrder object.

Parameters
incomingOrderPointer to the order message.

Definition at line 30 of file order_daemon.cpp.

Member Function Documentation

◆ compareBase()

bool CurrentOrder::compareBase ( string  startOfNewBaseNodeId,
int  startOfNewBaseSequenceId 
)

Compares start of new base and end of current base.

Parameters
startOfNewBaseNodeIdStart of new base node ID.
startOfNewBaseSequenceIdStart of new base sequence ID.
Returns
true if start of new base equals end of current base.
false if start of new base is not equal to end of current base.

Definition at line 59 of file order_daemon.cpp.

◆ compareOrderId()

bool CurrentOrder::compareOrderId ( string  orderIdToCompare)

Check if the given OrderID belongs to the current order.

Parameters
orderIdToCompareOrderID string that should be compared against

Definition at line 42 of file order_daemon.cpp.

◆ compareOrderUpdateId()

string CurrentOrder::compareOrderUpdateId ( int  orderUpdateIdToCompare)

Compares the incoming order update ID with the currently running order update ID.

Parameters
orderUpdateIdToCompareThe order update ID of the incoming order.
Returns
["EQUAL", "HIGHER", "LOWER"] if the new order update ID is equal, higher or lower compared to the running order update ID.

Definition at line 47 of file order_daemon.cpp.

◆ findNodeEdge()

string CurrentOrder::findNodeEdge ( int  currSequenceId)

Returns "NODE" or "EDGE" based on the sequence ID.

Parameters
currSequenceIdCurrent sequence ID.
Returns
"NODE" if AGV is positioned on a node and "EDGE" if AGV drives along an edge.

Definition at line 93 of file order_daemon.cpp.

◆ getLastNodeInBase()

vda5050_msgs::Node CurrentOrder::getLastNodeInBase ( )

Get the last released node. The last released node means the last node in current base.

Returns
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.

◆ getOrderId()

string CurrentOrder::getOrderId ( )

Get the order ID.

Returns
Current order ID.

Definition at line 65 of file order_daemon.cpp.

◆ getOrderUpdateId()

int CurrentOrder::getOrderUpdateId ( )

Get the order update ID.

Returns
Current order update ID.

Definition at line 70 of file order_daemon.cpp.

◆ isActive()

bool CurrentOrder::isActive ( )

Tells us whether or not the order is active.

Returns
true if order is active.
false if order is inactive.

Definition at line 80 of file order_daemon.cpp.

◆ sendActions()

void CurrentOrder::sendActions ( ros::Publisher  actionPublisher)

Sends all new actions to action daemon

Parameters
actionPublisherROS 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.

◆ sendEdgeStates()

void CurrentOrder::sendEdgeStates ( ros::Publisher  edgeStatesPublisher)

Sends all new edge states to state daemon.

Parameters
edgeStatesPublisherROS 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.

◆ sendNodeStates()

void CurrentOrder::sendNodeStates ( ros::Publisher  nodeStatesPublisher)

Sends all new node states to state daemon.

Parameters
nodeStatesPublisherROS 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.

◆ setOrderUpdateId()

void CurrentOrder::setOrderUpdateId ( int  incomingUpdateId)

Set the Order Update Id object.

Parameters
incomingUpdateIdIncoming order update ID.

Definition at line 75 of file order_daemon.cpp.

Member Data Documentation

◆ actionCancellationComplete

bool CurrentOrder::actionCancellationComplete

All actions cancelled in case of order cancellation.

Definition at line 48 of file order_daemon.h.

◆ actionsFinished

bool CurrentOrder::actionsFinished

All actions related to current edge or node finished?

Definition at line 45 of file order_daemon.h.

◆ actionStates

vector<string> CurrentOrder::actionStates

Vector containing the states of all active actions.

Definition at line 57 of file order_daemon.h.

◆ edgeStates

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.

◆ nodeStates

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.

◆ orderId

string CurrentOrder::orderId
private

Order ID of the order object.

Definition at line 34 of file order_daemon.h.

◆ orderUpdateId

int CurrentOrder::orderUpdateId
private

Current Order update ID of the order object.

Definition at line 37 of file order_daemon.h.

◆ zoneSetId

string CurrentOrder::zoneSetId
private

ZoneSetID of the order object.

Definition at line 40 of file order_daemon.h.


The documentation for this class was generated from the following files:


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