dummy_msg_creator.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 "dummy_msg_creator.h"
11 
12 OrderMsg::OrderMsg(vda5050_msgs::Order &msg, int last_released_node, std::string& last_released_nodeId)
13 {
14  _msg = msg;
15  _last_released_node = last_released_node;
16  _last_released_nodeId = last_released_nodeId;
17 }
18 
20 {
22 }
23 
24 void OrderMsg::create_nodes(int node_num, int node_released_num)
25 {
26 
27  this->_msg.nodes = std::vector<vda5050_msgs::Node>{};
28 
29  for (int i = 0; i < node_num; i++)
30  {
31  vda5050_msgs::Node subnode;
32  if (i == 0)
33  {
34  subnode.nodeId = _last_released_nodeId;
35  }
36  else
37  {
38  std::string rand_nodeId_str = this->rand_str(36);
39  // subnode.nodeId = "9b5d075a-8757-4002-929d-e245c624881b";
40  subnode.nodeId = rand_nodeId_str;
41  }
42 
43  subnode.sequenceId = this->_last_released_node + 2 * i;
44  subnode.nodeDescription = "Node based on device state: Header: 135";
45 
46  if (i < node_released_num)
47  {
48  subnode.released = true;
49  if (i == node_released_num - 1)
50  {
51  _last_released_nodeId = subnode.nodeId;
52  }
53  }
54  else
55  {
56  subnode.released = false;
57  }
58 
59  subnode.nodePosition.x = 10.0+5*i;
60  subnode.nodePosition.y = 10.0+5*i;
61  subnode.nodePosition.theta = 0.0;
62  subnode.nodePosition.allowedDeviationXY = 100.0;
63  subnode.nodePosition.allowedDeviationTheta = 100.0;
64  subnode.nodePosition.mapId = "6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
65  subnode.nodePosition.mapDescription = "Id: 6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
66  // create actions
67  std::vector<vda5050_msgs::Action> action_list;
68  vda5050_msgs::Action action = this->create_actions("wait");
69  action_list.push_back(action);
70  subnode.actions = action_list;
71 
72  this->_msg.nodes.push_back(subnode);
73  }
74  this->_last_released_node += 2 * (node_released_num - 1);
75 }
76 
77 void OrderMsg::create_edges(int node_num, int node_released_num)
78 {
79  this->_msg.edges = std::vector<vda5050_msgs::Edge>{};
80 
81  for (int i = 0; i < (node_num - 1); i++)
82  {
83  vda5050_msgs::Edge subedge;
84 
85  std::string rand_edgeId_str = this->rand_str(36);
86  subedge.edgeId = rand_edgeId_str;
87  // subedge.edgeId = "8b4894b6-a03b-49cb-8cd4-a904bcf1f471";
88 
89  subedge.sequenceId = this->_last_released_node + 2 * i + 1;
90  subedge.edgeDescription = "Edge connecting 9b5d075a-8757-4002-929d-e245c624881b to 6f61c844-e3d7-4018-85bf-c9d867fdd3d4";
91 
92  if (i < (node_released_num - 1))
93  {
94  subedge.released = true;
95  }
96  else
97  {
98  subedge.released = false;
99  }
100 
101  // subedge.startNodeId = "9b5d075a-8757-4002-929d-e245c624881b";
102  subedge.startNodeId = this->_msg.nodes[i].nodeId;
103  // subedge.endNodeId = "6f61c844-e3d7-4018-85bf-c9d867fdd3d4";
104  subedge.endNodeId = this->_msg.nodes[i + 1].nodeId;
105  subedge.maxSpeed = 0.0;
106  subedge.maxHeight = 0.0;
107  subedge.minHeight = 0.0;
108  subedge.orientation = 0.0;
109  subedge.direction = " ";
110  subedge.rotationAllowed = false;
111  subedge.maxRotationSpeed = 0.0;
112  subedge.trajectory.degree = 0.0;
113  subedge.trajectory.knotVector = std::vector<_Float64>{};
114  subedge.trajectory.controlPoints = std::vector<vda5050_msgs::ControlPoint>{};
115  subedge.length = 0.0;
116  subedge.actions = std::vector<vda5050_msgs::Action>{};
117  vda5050_msgs::Action action = this->create_actions("drop");
118  subedge.actions.push_back(action);
119 
120  this->_msg.edges.push_back(subedge);
121  }
122 }
123 
124 vda5050_msgs::Action OrderMsg::create_actions(std::string actionType)
125 {
126  vda5050_msgs::Action action;
127  action.actionType = actionType;
128  // generate random Id
129  std::string rand_actionId_str = this->rand_str(36);
130  action.actionId = rand_actionId_str;
131  action.actionDescription = actionType;
132  action.blockingType = "NONE";
133  action.actionParameters = std::vector<vda5050_msgs::ActionParameter>{};
134 
135  vda5050_msgs::ActionParameter actionParameter;
136  actionParameter.key = "waitFor";
137  actionParameter.value = "1";
138 
139  action.actionParameters.push_back(actionParameter);
140 
141  return action;
142 }
143 
144 void OrderMsg::create_example_order(int new_headerId,
145  std::string new_orderId,
146  int new_oderUpdateId,
147  int node_num,
148  int node_released_num)
149 {
150  // header
151  this->_msg.headerId = new_headerId;
152  this->_msg.timestamp = "10/6/2022 10:16:37 AM";
153  this->_msg.version = "v1";
154  this->_msg.manufacturer;
155  this->_msg.serialNumber;
156 
157  // contents
158  // msg.orderId = "f879f35e-a11f-4835-b13a-866c1bbc292a";
159  this->_msg.orderId = new_orderId;
160  this->_msg.orderUpdateId = new_oderUpdateId;
161  this->_msg.replace;
162  this->_msg.zoneSetId = " ";
163 
164  // nodes
165  this->create_nodes(node_num, node_released_num);
166 
167  // edges
168  this->create_edges(node_num, node_released_num);
169 }
170 
171 std::string OrderMsg::rand_str(const int len) /*length of string*/
172 {
173 
174  std::string str;
175  char c;
176  int idx;
177  /*iteratively add new char to the string*/
178  for (idx = 0; idx < len; idx++)
179  {
180  c = 'a' + rand() % 26;
181  str.push_back(c);
182  }
183  return str;
184 }
185 
186 vda5050_msgs::Order OrderMsg::get_msg()
187 {
188  return this->_msg;
189 }
190 
191 
192 // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
193 // old function
194 
195 // vda5050_msgs::Order create_example_order(int new_headerId,
196 // int new_orderId,
197 // int new_oderUpdateId,
198 // int node_num)
199 // {
200 // vda5050_msgs::Order msg;
201 // // header
202 // msg.headerId = new_headerId;
203 // msg.timestamp = "10/6/2022 10:16:37 AM";
204 // msg.version = "v1";
205 // msg.manufacturer;
206 // msg.serialNumber;
207 
208 // // contents
209 
210 // // msg.orderId = "f879f35e-a11f-4835-b13a-866c1bbc292a";
211 // msg.orderId = std::to_string(new_orderId);
212 // msg.orderUpdateId = new_oderUpdateId;
213 // msg.replace;
214 // msg.zoneSetId = " ";
215 
216 // // nodes
217 // msg.nodes = std::vector<vda5050_msgs::Node>{};
218 // for (int i = 0; i < node_num; i++)
219 // {
220 // vda5050_msgs::Node subnode;
221 // subnode.nodeId = "9b5d075a-8757-4002-929d-e245c624881b";
222 // subnode.sequenceId = 2 * i;
223 // subnode.nodeDescription = "Node based on device state: Header: 135";
224 // subnode.released = true;
225 // subnode.nodePosition.x = 10.0;
226 // subnode.nodePosition.y = 10.0;
227 // subnode.nodePosition.theta = 0.0;
228 // subnode.nodePosition.allowedDeviationXY = 100.0;
229 // subnode.nodePosition.allowedDeviationTheta = 100.0;
230 // subnode.nodePosition.mapId = "6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
231 // subnode.nodePosition.mapDescription = "Id: 6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
232 // subnode.actions = std::vector<vda5050_msgs::Action>{};
233 
234 // msg.nodes.push_back(subnode);
235 // }
236 
237 // // vda5050_msgs::Node node_2;
238 // // node_2.nodeId = "6f61c844-e3d7-4018-85bf-c9d867fdd3d4";
239 // // node_2.sequenceId = 2;
240 // // node_2.nodeDescription = "NEntry node for PointOfInterest d13d3dc4-33f8-44f3-9631-72e0668aa55b WaitPoint";
241 // // node_2.released = true;
242 // // node_2.nodePosition.x = 16.413757;
243 // // node_2.nodePosition.y = 19.216549;
244 // // node_2.nodePosition.theta = 0.0;
245 // // node_2.nodePosition.allowedDeviationXY = 0.7;
246 // // node_2.nodePosition.allowedDeviationTheta = 0.0;
247 // // node_2.nodePosition.mapId = "6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
248 // // node_2.nodePosition.mapDescription = "Map Id 6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
249 // // node_2.actions = std::vector<vda5050_msgs::Action>{};
250 
251 // // edges
252 // msg.edges = std::vector<vda5050_msgs::Edge>{};
253 
254 // for (int i = 0; i < (node_num - 1); i++)
255 // {
256 // vda5050_msgs::Edge subedge;
257 // subedge.edgeId = "8b4894b6-a03b-49cb-8cd4-a904bcf1f471";
258 // subedge.sequenceId = 2 * i + 1;
259 // subedge.edgeDescription = "Edge connecting 9b5d075a-8757-4002-929d-e245c624881b to 6f61c844-e3d7-4018-85bf-c9d867fdd3d4";
260 // subedge.released = true;
261 // subedge.startNodeId = "9b5d075a-8757-4002-929d-e245c624881b";
262 // subedge.endNodeId = "6f61c844-e3d7-4018-85bf-c9d867fdd3d4";
263 // subedge.maxSpeed = 0.0;
264 // subedge.maxHeight = 0.0;
265 // subedge.minHeight = 0.0;
266 // subedge.orientation = 0.0;
267 // subedge.direction = " ";
268 // subedge.rotationAllowed = false;
269 // subedge.maxRotationSpeed = 0.0;
270 // subedge.trajectory.degree = 0.0;
271 // subedge.trajectory.knotVector = std::vector<_Float64>{};
272 // subedge.trajectory.controlPoints = std::vector<vda5050_msgs::ControlPoint>{};
273 // subedge.length = 0.0;
274 // subedge.actions = std::vector<vda5050_msgs::Action>{};
275 
276 // msg.edges.push_back(subedge);
277 // }
278 
279 // return msg;
280 // }
dummy_msg_creator.h
OrderMsg::OrderMsg
OrderMsg()
Definition: dummy_msg_creator.cpp:19
OrderMsg::get_msg
vda5050_msgs::Order get_msg()
Definition: dummy_msg_creator.cpp:186
OrderMsg::create_edges
void create_edges(int node_num, int node_released_num)
Definition: dummy_msg_creator.cpp:77
OrderMsg::_last_released_node
int _last_released_node
Definition: dummy_msg_creator.h:44
OrderMsg::rand_str
std::string rand_str(const int len)
Definition: dummy_msg_creator.cpp:171
OrderMsg::create_example_order
void create_example_order(int new_headerId, std::string new_orderId, int new_oderUpdateId, int node_num, int node_released_num)
Definition: dummy_msg_creator.cpp:144
OrderMsg::_last_released_nodeId
std::string _last_released_nodeId
Definition: dummy_msg_creator.h:45
OrderMsg::_msg
vda5050_msgs::Order _msg
Definition: dummy_msg_creator.h:43
OrderMsg::create_nodes
void create_nodes(int node_num, int node_released_num)
Definition: dummy_msg_creator.cpp:24
OrderMsg::create_actions
vda5050_msgs::Action create_actions(std::string actionType)
Definition: dummy_msg_creator.cpp:124


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