order_mockup.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 "dummy_msg_creator.h"
12 #include "dummy_msg_creator.cpp"
13 
14 int main(int argc, char **argv)
15 {
16  ros::init(argc, argv, "order_mockup");
18 
19  // initialize a publisher
20  ros::Publisher order_pub = n.advertise<vda5050_msgs::Order>("order", 1000);
21 
22  // read parameters from server
23  float new_order_freq;
24  float order_update_freq;
25  int num_of_nodes;
26  int num_of_released_nodes;
27 
28 
29  n.getParam("order_mockup/new_order_frequency", new_order_freq);
30  ROS_INFO("New order is published every %fs", new_order_freq);
31  n.getParam("order_mockup/order_update_frequency", order_update_freq);
32  ROS_INFO("Order update is published every %fs", order_update_freq);
33  n.getParam("order_mockup/num_of_nodes", num_of_nodes);
34  ROS_INFO("The number of nodes every order is %d", num_of_nodes);
35  n.getParam("order_mockup/num_of_released_nodes", num_of_released_nodes);
36  ROS_INFO("The number of released nodes every order is %d", num_of_released_nodes);
37 
38  // set publish frequency
39  auto freq = 1 / order_update_freq;
40  int divisor = new_order_freq / order_update_freq;
41 
42  ros::Rate loop_rate(freq);
43  int count = 0;
44 
45  // initialize the chatacteristics of publisher
46 
47  OrderMsg *OrderMsgPtr = new OrderMsg();
48  int new_headerId = 0;
49  std::string new_orderId = OrderMsgPtr->rand_str(36);
50  int new_oderUpdateId = 0;
51  int node_num = num_of_nodes;
52  int node_released_num = num_of_released_nodes;
53 
54  // publish the msgs
55  while (ros::ok())
56  {
57 
58  OrderMsgPtr->create_example_order(new_headerId,
59  new_orderId,
60  new_oderUpdateId,
61  node_num,
62  node_released_num);
63 
64  order_pub.publish(OrderMsgPtr->get_msg());
65 
66  count++;
67  new_oderUpdateId++;
68 
69  if (count % divisor == 0)
70  {
71  new_headerId++;
72  new_orderId = OrderMsgPtr->rand_str(36);
73  new_oderUpdateId = 0;
74  }
75 
76  ros::spinOnce();
77  loop_rate.sleep();
78  }
79 
80  delete OrderMsgPtr;
81  return 0;
82 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void create_example_order(int new_headerId, std::string new_orderId, int new_oderUpdateId, int node_num, int node_released_num)
std::string rand_str(const int len)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
ROSCPP_DECL void spinOnce()
vda5050_msgs::Order get_msg()


vda5050_connector
Author(s): Florian Rothmeyer , Florian Spiegel
autogenerated on Tue Mar 21 2023 02:52:00