#include <action_daemon.h>

Public Member Functions | |
| ActionDaemon () | |
| void | AddActionToList (const vda5050_msgs::Action *incomingAction, string orderId, string state) |
| void | AgvActionStateCallback (const vda5050_msgs::ActionState::ConstPtr &msg) |
| bool | checkDriving () |
| void | DrivingCallback (const std_msgs::Bool::ConstPtr &msg) |
| shared_ptr< ActionElement > | findAction (string actionId) |
| vector< shared_ptr< ActionElement > > | GetActionsToCancel (string orderIdToCancel) |
| vector< shared_ptr< ActionElement > > | GetRunningActions () |
| vector< shared_ptr< ActionElement > > | GetRunningPausedActions () |
| void | InstantActionsCallback (const vda5050_msgs::InstantActions::ConstPtr &msg) |
| void | LinkPublishTopics (ros::NodeHandle *nh) |
| void | LinkSubscriptionTopics (ros::NodeHandle *nh) |
| void | OrderActionsCallback (const vda5050_msgs::OrderActions::ConstPtr &msg) |
| void | OrderCancelCallback (const std_msgs::String &msg) |
| void | OrderTriggerCallback (const std_msgs::String &msg) |
| void | UpdateActions () |
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 | |
| deque< vda5050_msgs::Action > | instantActionQueue |
| deque< vda5050_msgs::Action > | orderActionQueue |
| vector< string > | ordersSucCancelled |
Protected Attributes inherited from Daemon | |
| ros::Publisher | errorPublisher |
| std::map< std::string, ros::Publisher > | messagePublisher |
| ros::NodeHandle | nh |
| std::map< std::string, ros::Subscriber > | subscribers |
Private Attributes | |
| ros::Publisher | actionStatesPub |
| vector< shared_ptr< ActionElement > > | activeActionsList |
| ros::Publisher | allActionsCancelledPub |
| bool | isDriving |
| ros::Subscriber | orderActionSub |
| vector< orderToCancel > | orderCancellations |
| ros::Publisher | orderCancelPub |
| ros::Subscriber | orderCancelSub |
| ros::Subscriber | orderTriggerSub |
Daemon for processing of VDA 5050 action messages.
Definition at line 137 of file action_daemon.h.
| ActionDaemon::ActionDaemon | ( | ) |
Constructor for the action daemon.
Initialize internal topics
Definition at line 79 of file action_daemon.cpp.
| void ActionDaemon::AddActionToList | ( | const vda5050_msgs::Action * | incomingAction, |
| string | orderId, | ||
| string | state | ||
| ) |
Adds a new action to the activeActionsList list.
| incomingAction | Incoming action |
| orderId | ID of the related order. |
| state | State of the incoming action. |
Definition at line 351 of file action_daemon.cpp.
| void ActionDaemon::AgvActionStateCallback | ( | const vda5050_msgs::ActionState::ConstPtr & | msg | ) |
Callback for agvActionState topic from AGV. This callback runs when a new message arrives at the /agvActionState topic. The message contains the state of a single action. The state is used to fill the actionStates sent to the state daemon and to track the current state for action blocking evaluation.
| msg | Message including the state of an action. |
Definition at line 301 of file action_daemon.cpp.
| bool ActionDaemon::checkDriving | ( | ) |
Checks if the AGV is driving and stops driving if so.
Definition at line 357 of file action_daemon.cpp.
| void ActionDaemon::DrivingCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Callback for driving topic from AGV. This callback runs when a new message arrives at the /driving topic. The message contains the driving state of the AGV.
| msg | Message including the driving state of the AGV. |
Definition at line 346 of file action_daemon.cpp.
| shared_ptr< ActionElement > ActionDaemon::findAction | ( | string | actionId | ) |
Finds and returns the action with the requested ID. Finds the action in the activeActionsList list which has the requested ID. The corresponding action is returned.
| actionId | ID of the action to find within the active Actions. |
Definition at line 410 of file action_daemon.cpp.
| vector< shared_ptr< ActionElement > > ActionDaemon::GetActionsToCancel | ( | string | orderIdToCancel | ) |
Get all actions from activeActionsList which should be cancelled.
| orderIdToCancel | ID of the order to cancel. |
Definition at line 396 of file action_daemon.cpp.
| vector< shared_ptr< ActionElement > > ActionDaemon::GetRunningActions | ( | ) |
Get all running actions.
Definition at line 370 of file action_daemon.cpp.
| vector< shared_ptr< ActionElement > > ActionDaemon::GetRunningPausedActions | ( | ) |
Get all running or paused actions.
Definition at line 383 of file action_daemon.cpp.
| void ActionDaemon::InstantActionsCallback | ( | const vda5050_msgs::InstantActions::ConstPtr & | msg | ) |
Callback for instant Actions topic from the fleet controller. This callback is called when a new message arrives at the /instantActions topic. Actions are queued into a FIFO queue. The first element of that queue is sent to the AGV for execution.
| msg | Message including the incoming instant action. |
Add action to active actions list
Initialize order ID variable
Decide if the action contains an order cancel
New actions to cancel
Add orderId to orderCancellations list and get all actions to cancel
Cancel actions from newActionsToCancel list
Wating actions can simply be removed as long as they have not been sent to the AGV
Check if Action has already been sent to AGV (in activeActionsList but not in queue)
action already sent to AGV
Send action cancel request to AGV
action not sent to AGV yet
action triggered and in queue (but still not sent to AGV)
delete action from queue
delete from newActionsToCancel
send failed state to state daemon
delete from activeActionsList
Running/Initializing/Paused actions must be stopped
Send action cancel request to AGV
Create new order to cancel
Add all remaining new actions to cancel to the list
If no action to cancel remains (i.e. no action has been sent to the AGV already)
-> remove order ID from cancellation list in update loop
Add new order to cancel to list
Send cancel request to order daemon
if the action contains no order cancel
Push to instant action queue
Create and publish action state msg
Description necessary?
Definition at line 168 of file action_daemon.cpp.
| void ActionDaemon::LinkPublishTopics | ( | ros::NodeHandle * | nh | ) |
Links all external publishing topics.
| nh | ROS node handle for action daemon. |
Definition at line 93 of file action_daemon.cpp.
| void ActionDaemon::LinkSubscriptionTopics | ( | ros::NodeHandle * | nh | ) |
Links all external subscribing topics
| nh | ROS node handle for action daemon. |
Definition at line 113 of file action_daemon.cpp.
| void ActionDaemon::OrderActionsCallback | ( | const vda5050_msgs::OrderActions::ConstPtr & | msg | ) |
Callback for order actions topic from order_daemon. This callback is called when a new message arrives at the /orderAction topic. Actions are queued into a FIFO queue. The first element of that queue is sent to the AGV for execution.
| msg | Message including the incoming order action. |
Add action to active actions list
Create and publish action state msg
Description necessary?
Definition at line 127 of file action_daemon.cpp.
| void ActionDaemon::OrderCancelCallback | ( | const std_msgs::String & | msg | ) |
Callback to process response to order cancel request from order daemon. This callback is called when a new message arrives at the /orderCancelResponse topic. When a order cancel request was sent to the order daemon, it sends the corresponding order id to cancel via the /orderCancelResponse topic back to the action daemon to confirm the cancellation.
| msg | Message including the ID of the cancelled order. |
Definition at line 163 of file action_daemon.cpp.
| void ActionDaemon::OrderTriggerCallback | ( | const std_msgs::String & | msg | ) |
Callback for order trigger topic from order daemon. This callback is called when a new message arrives at the /orderTrigger topic. A trigger contains the ID of an action and triggers adding the corresponding action to the order action queue.
| msg | Message including the action ID to trigger. |
Push action to queue
Definition at line 146 of file action_daemon.cpp.
| void ActionDaemon::UpdateActions | ( | ) |
Processes actions based on their type. The UpdateActions() method represents the main event loop. Based on the order and instan action queues, the method processes incoming actions and pauses driving state and pauses/resumes other actions.
check if orders must be cancelled -> block all actions
Remove failed/finished actions from observing list
TODO: FUNKTIONIERT NICHT!<--------------------------------------------------------------—
TODO: FUNKTIONIERT NICHT!<--------------------------------------------------------------—
Only check the order cancel state, if all actions are cancelled
send all actions cancelled signal to order daemon
Check if order has been cancelled by order daemon
If order has been cancelled by order deamon
Send action state finished
Create and publish action state msg
Remove instant action from active actions list
Remove order to cancel from orderSucCancelled list
Remove order to cancel from orderCancellations list
Delete from List
Instant action routine -> block order actions
get running actions
hard blocking action running?
new instant action blocking hard
set sentToAgv to true
send action
Pause all actions
set sentToAgv to true
send action
set sentToAgv to true
send action
Pause all actions
no action running
set sentToAgv to true
send action to AGV
Order action routine
get running actions
hard blocking action running?
resume actions paused by instant actions
no actions to resume
new action blocking hard
TODO: Check if last action still running
If driving -> stop, else publish action
set sentToAgv to true
send action to AGV
new action blocking soft
If driving -> stop, else publish action
set sentToAgv to true
send action to AGV
new action not blocking
set sentToAgv to true
send action to AGV
no action running
set sentToAgv to true
send action to AGV
Definition at line 421 of file action_daemon.cpp.
|
private |
States of actions from action_daemon to state_daemon.
Definition at line 161 of file action_daemon.h.
|
private |
List of actions to track all active actions.
Definition at line 140 of file action_daemon.h.
|
private |
All actions of one order to cancel cancelled from action_daemon to order_daemon.
Definition at line 167 of file action_daemon.h.
|
protected |
Queue for keeping track of instant actions.
Definition at line 180 of file action_daemon.h.
|
private |
True, if the vehicle is driving.
Definition at line 172 of file action_daemon.h.
|
protected |
Queue for keeping track of order actions.
Definition at line 177 of file action_daemon.h.
|
private |
Declare all ROS subscriber and publisher topics for internal communication Ordinary order actions from order_daemon to action_daemon.
Definition at line 152 of file action_daemon.h.
|
private |
List of all orders to cancel and their respective order ID.
Definition at line 143 of file action_daemon.h.
|
private |
Cancelled actions from action_daemon to order_daemon.
Definition at line 164 of file action_daemon.h.
|
private |
Order daemon sends response to order cancel request.
Definition at line 158 of file action_daemon.h.
|
protected |
List of all orders cancelled by order daemon.
Definition at line 183 of file action_daemon.h.
|
private |
Order daemon triggers actions.
Definition at line 155 of file action_daemon.h.