Go to the documentation of this file.
14 int main(
int argc,
char **argv)
24 float order_update_freq;
26 int num_of_released_nodes;
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);
39 auto freq = 1 / order_update_freq;
40 int divisor = new_order_freq / order_update_freq;
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;
69 if (count % divisor == 0)
72 new_orderId = OrderMsgPtr->
rand_str(36);
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
vda5050_msgs::Order get_msg()
std::string rand_str(const int len)
void create_example_order(int new_headerId, std::string new_orderId, int new_oderUpdateId, int node_num, int node_released_num)
vda5050_connector
Author(s): Florian Rothmeyer
, Florian Spiegel
autogenerated on Wed Mar 22 2023 02:38:56