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

#include <order_daemon.h>

Inheritance diagram for OrderDaemon:
Inheritance graph
[legend]

Public Member Functions

void ActionStateCallback (const vda5050_msgs::ActionState::ConstPtr &msg)
 
void AgvPositionCallback (const vda5050_msgs::AGVPosition::ConstPtr &msg)
 
void allActionsCancelledCallback (const std_msgs::String::ConstPtr &msg)
 
void appendNewOrder (const vda5050_msgs::Order::ConstPtr &msg)
 
void DrivingCallback (const std_msgs::Bool::ConstPtr &msg)
 
bool inDevRange (vda5050_msgs::Node node)
 
void LinkPublishTopics (ros::NodeHandle *nh)
 
void LinkSubscriptionTopics (ros::NodeHandle *nh)
 
void OrderCallback (const vda5050_msgs::Order::ConstPtr &msg)
 
void OrderCancelRequestCallback (const std_msgs::String::ConstPtr &msg)
 
 OrderDaemon ()
 
void orderUpdateError (string orderId, int orderUpdateId)
 
void orderValidationError (string orderId, int orderUpdateId)
 
void sendMotionCommand ()
 
void startNewOrder (const vda5050_msgs::Order::ConstPtr &msg)
 
void triggerNewActions (string nodeOrEdge)
 
void updateExistingOrder (const vda5050_msgs::Order::ConstPtr &msg)
 
void UpdateOrders ()
 
bool validationCheck (const vda5050_msgs::Order::ConstPtr &msg)
 
- Public Member Functions inherited from Daemon
bool CheckPassedTime ()
 
bool CheckRange (double lowerRange, double upperRange, double value, std::string msg_name)
 
bool CheckTopic (std::string str1, std::string str2)
 
bool CompareStrings (std::string str1, std::string str2)
 
std::string CreateTimestamp ()
 
void createTopicStructurePrefix ()
 
 Daemon ()
 
 Daemon (ros::NodeHandle *nh, std::string daemonName)
 
vda5050_msgs::Header GetHeader ()
 
std::vector< std::string > GetMsgList (std::map< std::string, std::string > topicList)
 
std::string GetParameter (std::string param)
 
std::string GetTopic (std::string hierarchical_topic)
 
std::map< std::string, std::string > GetTopicPublisherList ()
 
std::string getTopicStructurePrefix ()
 
std::map< std::string, std::string > GetTopicSubscriberList ()
 
void InitHeaderInfo ()
 
void LinkErrorTopics (ros::NodeHandle *nh)
 
void PublishState ()
 
std::map< std::string, std::string > ReadTopicParams (ros::NodeHandle *nh, std::string paramTopicName)
 
void UpdateHeader ()
 
void UpdateState ()
 

Protected Attributes

int currSequenceId
 
bool isDriving
 
vector< string > ordersToCancel
 
- Protected Attributes inherited from Daemon
ros::Publisher errorPublisher
 
std::map< std::string, ros::PublishermessagePublisher
 
ros::NodeHandle nh
 
std::map< std::string, ros::Subscribersubscribers
 

Private Attributes

AGVPosition agvPosition
 
ros::Subscriber agvPositionSub
 
ros::Subscriber allActionsCancelledSub
 
vector< CurrentOrdercurrentOrders
 
ros::Publisher edgeStatesPub
 
ros::Publisher lastNodeIdPub
 
ros::Publisher lastNodeSequenceIdPub
 
ros::Publisher nodeStatesPub
 
ros::Publisher orderActionPub
 
ros::Publisher orderCancelPub
 
ros::Subscriber orderCancelSub
 
ros::Publisher orderIdPub
 
ros::Publisher orderTriggerPub
 
ros::Publisher orderUpdateIdPub
 

Detailed Description

Daemon for processing VDA 5050 order messages.

Definition at line 229 of file order_daemon.h.

Constructor & Destructor Documentation

◆ OrderDaemon()

OrderDaemon::OrderDaemon ( )

Constructor for OrderDaemon objects. Links all internal and external ROS topics.

Initialize external ROS topics

Initialize internal ROS topics

Definition at line 213 of file order_daemon.cpp.

Member Function Documentation

◆ ActionStateCallback()

void OrderDaemon::ActionStateCallback ( const vda5050_msgs::ActionState::ConstPtr &  msg)

Tracks action states to decide if the current node/edge is finished and can be left.

Parameters
msgIncoming action state message.

TODO: Abort order and delete complete actionList

Definition at line 451 of file order_daemon.cpp.

◆ AgvPositionCallback()

void OrderDaemon::AgvPositionCallback ( const vda5050_msgs::AGVPosition::ConstPtr &  msg)

Updates the saved position with the incoming position. Depending on position and action states it decides whether or not the current node or edge is finished and the next one can be started.

Parameters
msgIncoming position update message.

reset actions finished flag

delete edgeState from queue

Further node in base?

No further node -> error; all orders must begin and end with a node

TODO: Send on error topic?, How to proceed?

reset actionsFinished flag

send last node ID to state daemon

send last node sequence ID to state daemon

delete nodeState from queue

further edge in base?

-> must be placed after nodeList.pop() to ensure that correct next node position is sent

send order ID to state daemon

send order update ID to state daemon

Definition at line 472 of file order_daemon.cpp.

◆ allActionsCancelledCallback()

void OrderDaemon::allActionsCancelledCallback ( const std_msgs::String::ConstPtr &  msg)

Callback for incoming information about the cancellation of all actions. Sets flag in currentOrders in case all related actions have been successfully cancelled in case of order cancellation.

Parameters
msgOrder ID of the order to cancel.

Definition at line 440 of file order_daemon.cpp.

◆ appendNewOrder()

void OrderDaemon::appendNewOrder ( const vda5050_msgs::Order::ConstPtr &  msg)

Appends the new order instead of the horizon.

Parameters
msgNewly arrived order.

clear horizon

add new order

send node and edge states to state daemon

Definition at line 604 of file order_daemon.cpp.

◆ DrivingCallback()

void OrderDaemon::DrivingCallback ( const std_msgs::Bool::ConstPtr &  msg)

Keeps track of the driving state of the AGV.

Parameters
msgDriving state message from AGV.

Definition at line 559 of file order_daemon.cpp.

◆ inDevRange()

bool OrderDaemon::inDevRange ( vda5050_msgs::Node  node)

Decides whether the AGV position is within the permissible deviation range of the given node.

Parameters
nodenode to calculate the distance to
Returns
true if AGV position is in the deviation range
false if AGV position is not in the deviation range

Definition at line 273 of file order_daemon.cpp.

◆ LinkPublishTopics()

void OrderDaemon::LinkPublishTopics ( ros::NodeHandle nh)

Links all external publishing topics.

Parameters
nhROS node handle for order daemon.

Definition at line 234 of file order_daemon.cpp.

◆ LinkSubscriptionTopics()

void OrderDaemon::LinkSubscriptionTopics ( ros::NodeHandle nh)

Links all external subscribing topics

Parameters
nhROS node handle for order daemon.

Definition at line 251 of file order_daemon.cpp.

◆ OrderCallback()

void OrderDaemon::OrderCallback ( const vda5050_msgs::Order::ConstPtr &  msg)

Callback for incoming orders. Decides if the incoming order should be appended or rejected according to the flowchart in VDA 5050.

Parameters
msgIncoming order message.

Definition at line 348 of file order_daemon.cpp.

◆ OrderCancelRequestCallback()

void OrderDaemon::OrderCancelRequestCallback ( const std_msgs::String::ConstPtr &  msg)

Callback for incoming cancel requests. When an instantAction message with a cancel request arrives at the action daemon, the request is transferred to the order daemon by this topic.

Parameters
msgMessage containing the order cancel request.

Definition at line 420 of file order_daemon.cpp.

◆ orderUpdateError()

void OrderDaemon::orderUpdateError ( string  orderId,
int  orderUpdateId 
)

Sends an order update error to the error topic.

Parameters
orderIdOrder ID of the incoming order.
orderUpdateIdOrder updeate ID of the incoming order.

Definition at line 700 of file order_daemon.cpp.

◆ orderValidationError()

void OrderDaemon::orderValidationError ( string  orderId,
int  orderUpdateId 
)

Sends an order validation error to the error topic.

Parameters
orderIdOrder ID of the incoming order.
orderUpdateIdOrder update ID of the incoming order.

Definition at line 709 of file order_daemon.cpp.

◆ sendMotionCommand()

void OrderDaemon::sendMotionCommand ( )

Sends motion commands to the AGV.

TODO: catch exceptions if certain optional keys are not inlcuded in the message

check if trajectory is in use

Definition at line 321 of file order_daemon.cpp.

◆ startNewOrder()

void OrderDaemon::startNewOrder ( const vda5050_msgs::Order::ConstPtr &  msg)

Creates a new order element if no order exists.

Parameters
msgNewly arrived order.

create new order element

set sequence ID

send motion commands to AGV

send actions to action daemon

trigger Actions in case of first node containing actions

send node and edge states to state daemon

send order ID to state daemon

send order update ID to state daemon

Definition at line 564 of file order_daemon.cpp.

◆ triggerNewActions()

void OrderDaemon::triggerNewActions ( string  nodeOrEdge)

Triggers actions of the following node or edge.

Parameters
nodeOrEdgeis the AGV currently on a node or an edge?

Definition at line 281 of file order_daemon.cpp.

◆ updateExistingOrder()

void OrderDaemon::updateExistingOrder ( const vda5050_msgs::Order::ConstPtr &  msg)

Updates the existing order (i.e. release the horizon).

Parameters
msgNewly arrived order.

clear horizon

append nodeStates/edgeStates

TODO: Frage: wirklich front(), wenn mehrere orders vorhanden?

send actions to action daemon

TODO: Overhead by creating a new order object!

send node and edge states to state daemon

send order update ID to state daemon

Definition at line 626 of file order_daemon.cpp.

◆ UpdateOrders()

void OrderDaemon::UpdateOrders ( )

Main loop of the daemon. The routine consists of the following steps:

  • get order actions
  • get instantAction topics
  • calculate queue
  • send queue to agv
  • send order cancellations to order_daemon
  • send action status to state_daemon

remove order from currentOrders

send response to action daemon

remove order ID from ordersToCancel

Definition at line 660 of file order_daemon.cpp.

◆ validationCheck()

bool OrderDaemon::validationCheck ( const vda5050_msgs::Order::ConstPtr &  msg)

Checks if the incoming order is valid.

Parameters
msgIncoming order message.
Returns
true if order is valid.
false if order is not valid.

TODO: How to validation check?

Maybe depending on AGV's capabilities (e.g. track planning etc.)

Check if number edges is number nodes-1

Definition at line 265 of file order_daemon.cpp.

Member Data Documentation

◆ agvPosition

AGVPosition OrderDaemon::agvPosition
private

Currently active order.

Definition at line 235 of file order_daemon.h.

◆ agvPositionSub

ros::Subscriber OrderDaemon::agvPositionSub
private

Position data from AGV.

Definition at line 246 of file order_daemon.h.

◆ allActionsCancelledSub

ros::Subscriber OrderDaemon::allActionsCancelledSub
private

Response from action daemon if all actions of a order to cancel are successfully cancelled.

Definition at line 249 of file order_daemon.h.

◆ currentOrders

vector<CurrentOrder> OrderDaemon::currentOrders
private

Current order.

Definition at line 232 of file order_daemon.h.

◆ currSequenceId

int OrderDaemon::currSequenceId
protected

true, if the AGV currently moves on an edge.

Definition at line 289 of file order_daemon.h.

◆ edgeStatesPub

ros::Publisher OrderDaemon::edgeStatesPub
private

Edge state transfer topic (to state daemon).

Definition at line 266 of file order_daemon.h.

◆ isDriving

bool OrderDaemon::isDriving
protected

true if vehicle is driving.

Definition at line 286 of file order_daemon.h.

◆ lastNodeIdPub

ros::Publisher OrderDaemon::lastNodeIdPub
private

Last node ID; changes when a node is left.

Definition at line 269 of file order_daemon.h.

◆ lastNodeSequenceIdPub

ros::Publisher OrderDaemon::lastNodeSequenceIdPub
private

Last node sequence ID; changes when a node is left.

Definition at line 272 of file order_daemon.h.

◆ nodeStatesPub

ros::Publisher OrderDaemon::nodeStatesPub
private

Node state transfer topic (to state daemon).

Definition at line 263 of file order_daemon.h.

◆ orderActionPub

ros::Publisher OrderDaemon::orderActionPub
private

Ordinary order actions from order_daemon to action_daemon.

Definition at line 254 of file order_daemon.h.

◆ orderCancelPub

ros::Publisher OrderDaemon::orderCancelPub
private

Response to cancel request.

Definition at line 257 of file order_daemon.h.

◆ orderCancelSub

ros::Subscriber OrderDaemon::orderCancelSub
private

Declare all ROS subscriber and publisher topics for internal communication. Cancel request from action daemon.

Definition at line 243 of file order_daemon.h.

◆ orderIdPub

ros::Publisher OrderDaemon::orderIdPub
private

Order ID; changes when a new order is started.

Definition at line 275 of file order_daemon.h.

◆ ordersToCancel

vector<string> OrderDaemon::ordersToCancel
protected

Stores all order IDs to cancel.

Definition at line 283 of file order_daemon.h.

◆ orderTriggerPub

ros::Publisher OrderDaemon::orderTriggerPub
private

Triggers actions when AGV arrives at edge or node.

Definition at line 260 of file order_daemon.h.

◆ orderUpdateIdPub

ros::Publisher OrderDaemon::orderUpdateIdPub
private

Order ID; changes when a new order or order update is started.

Definition at line 278 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