src
mock_ups
order_mockup
logic_examinator.cpp
Go to the documentation of this file.
1
/*
2
* Copyright 2022 Technical University of Munich, Chair of Materials Handling,
3
* Material Flow, Logistics – All Rights Reserved
4
*
5
* You may use, distribute and modify this code under the terms of the 3-clause
6
* BSD license. You should have received a copy of that license with this file.
7
* If not, please write to {kontakt.fml@ed.tum.de}.
8
*/
9
10
#include "
ros/ros.h
"
11
#include "vda5050_msgs/Order.h"
12
#include "vda5050_msgs/Node.h"
13
14
class
OrderExaminator
15
{
16
// Declare ROS things
17
ros::NodeHandle
_nh
;
18
ros::Subscriber
_sub
;
19
vda5050_msgs::Order
_cur_order
;
20
21
22
public
:
23
// Constructor
24
OrderExaminator
(std::string desired_topic)
25
{
26
// Define publisher
27
_sub
=
_nh
.
subscribe
(desired_topic, 10, &
OrderExaminator::orderCallback
,
this
);
28
}
29
30
// Callback
31
void
orderCallback
(
const
vda5050_msgs::Order::ConstPtr &order)
32
{
33
if
(
_cur_order
.orderId.size() == 0)
34
{
35
_cur_order
= *order;
36
return
;
37
}
38
39
vda5050_msgs::Node last_base;
40
41
for
(
auto
i = 0; i <
_cur_order
.nodes.size(); i++)
42
{
43
if
(
_cur_order
.nodes[i].released ==
false
)
44
{
45
assert(i != 0);
46
last_base =
_cur_order
.nodes[i-1];
47
break
;
48
}
49
}
50
51
// situation of new order comes
52
if
(order->orderId !=
_cur_order
.orderId)
53
{
54
// storage all of the base nodes
55
// std::vector<vda5050_msgs::Node> base;
56
// for (auto &node : _cur_order.nodes)
57
// {
58
// if (node.released == true)
59
// {
60
// base.push_back(node);
61
// }
62
// }
63
64
if
(order->nodes[0].nodeId == last_base.nodeId && order->nodes[0].sequenceId == last_base.sequenceId)
65
{
66
// print error info in command window
67
ROS_INFO
(
"new order correctly published!"
);
68
}
69
else
70
{
71
ROS_INFO
(
"new order rejected! error: start of new base != end of the current base."
);
72
}
73
}
74
// situation of order updates
75
else
76
{
77
if
(order->orderUpdateId <
_cur_order
.orderUpdateId)
78
{
79
ROS_INFO
(
"order update rejected! error: new orderUpdateId is lower as current orderUpdateId."
);
80
}
81
else
if
(order->orderUpdateId ==
_cur_order
.orderUpdateId)
82
{
83
ROS_INFO
(
"order update discarded! error: new orderUpdateId is same as current orderUpdateId."
);
84
}
85
else
86
{
87
if
(order->nodes.size() == 0 || order->edges.size() == 0)
88
{
89
ROS_INFO
(
"order update inactive! error: nodeStates or edgeStates empty."
);
90
}
91
else
92
{
93
94
// std::vector<vda5050_msgs::Node> base;
95
// for (auto &node : _cur_order.nodes)
96
// {
97
// if (node.released == true)
98
// {
99
// base.push_back(node);
100
// }
101
// }
102
if
(order->nodes[0].nodeId == last_base.nodeId && order->nodes[0].sequenceId == last_base.sequenceId)
103
{
104
// print error info in command window
105
ROS_INFO
(
"updated order correctly published!"
);
106
}
107
else
108
{
109
ROS_INFO
(
"updated order rejected! error: start of new base != end of the current base."
);
110
}
111
}
112
}
113
}
114
_cur_order
= *order;
115
}
116
};
117
118
// Main function
119
int
main
(
int
argc,
char
**argv)
120
{
121
// initialize node
122
ros::init
(argc, argv,
"order_logic_examinator"
);
123
ros::NodeHandle
nh;
124
125
// initialize classes
126
OrderExaminator
examinator_node(
"/order_from_mc"
);
127
128
ros::spin
();
129
130
return
0;
131
}
OrderExaminator::_sub
ros::Subscriber _sub
Definition:
logic_examinator.cpp:18
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
OrderExaminator::orderCallback
void orderCallback(const vda5050_msgs::Order::ConstPtr &order)
Definition:
logic_examinator.cpp:31
OrderExaminator
Definition:
logic_examinator.cpp:14
OrderExaminator::_nh
ros::NodeHandle _nh
Definition:
logic_examinator.cpp:17
OrderExaminator::OrderExaminator
OrderExaminator(std::string desired_topic)
Definition:
logic_examinator.cpp:24
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::spin
ROSCPP_DECL void spin()
OrderExaminator::_cur_order
vda5050_msgs::Order _cur_order
Definition:
logic_examinator.cpp:19
main
int main(int argc, char **argv)
Definition:
logic_examinator.cpp:119
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle
ros::Subscriber
vda5050_connector
Author(s): Florian Rothmeyer
, Florian Spiegel
autogenerated on Wed Mar 22 2023 02:38:56