action_msg_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 "std_msgs/String.h"
12 #include "std_msgs/Bool.h"
13 #include <iostream>
14 #include <vector>
15 #include <string>
16 #include <list>
17 #include "vda5050_msgs/Action.h"
18 #include "vda5050_msgs/OrderActions.h"
19 #include "vda5050_msgs/ActionState.h"
20 #include "vda5050_msgs/InstantActions.h"
21 #include <random>
22 #include <sstream>
23 
24 using namespace std;
25 
26 namespace uuid {
27  static std::random_device rd;
28  static std::mt19937 gen(rd());
29  static std::uniform_int_distribution<> dis(0, 15);
30  static std::uniform_int_distribution<> dis2(8, 11);
31 
32  std::string generate_uuid_v4() {
33  std::stringstream ss;
34  int i;
35  ss << std::hex;
36  for (i = 0; i < 8; i++) {
37  ss << dis(gen);
38  }
39  ss << "-";
40  for (i = 0; i < 4; i++) {
41  ss << dis(gen);
42  }
43  ss << "-4";
44  for (i = 0; i < 3; i++) {
45  ss << dis(gen);
46  }
47  ss << "-";
48  ss << dis2(gen);
49  for (i = 0; i < 3; i++) {
50  ss << dis(gen);
51  }
52  ss << "-";
53  for (i = 0; i < 12; i++) {
54  ss << dis(gen);
55  };
56  return ss.str();
57  }
58 }
59 
60 void send_order_action(ros::Publisher *pub, string ID)
61 {
62  vda5050_msgs::OrderActions msg;
63  vda5050_msgs::Action action;
64  vda5050_msgs::ActionParameter param;
65 
66  msg.orderId = "ABC";
67 
68  std::string actionID;
69 
70  if (ID == "0")
71  actionID = uuid::generate_uuid_v4();
72  else
73  actionID = ID;
74  std::string actionType = "Hebe Gabel";
75  std::string blockingType = "HARD";
76  std::string actionDescription = "Hebe die Gabel der Weisheit";
77 
78 
79  action.actionId = actionID;
80  action.actionType = "Hebe Gabel";
81  action.blockingType = "HARD";
82  action.actionDescription = "Hebe die Gabel der Weisheit";
83  msg.orderActions.push_back(action);
84 
85  param.key = "Hoehe";
86  param.value = "50";
87  msg.orderActions.front().actionParameters.push_back(param);
88 
89  pub->publish(msg);
90  ROS_INFO_STREAM("New order action sent!");
91 }
92 
94 {
95  vda5050_msgs::InstantActions instAction;
96  vda5050_msgs::Action msg1;
97  vda5050_msgs::Action msg2;
98  vda5050_msgs::ActionParameter param1;
99  vda5050_msgs::ActionParameter param2;
100 
101  instAction.headerId = 123456;
102  instAction.manufacturer = "AGV";
103  instAction.serialNumber = "1234567489";
104  instAction.timestamp = "asdas1sad3";
105  instAction.version = "v1.0";
106 
107  msg1.actionId = uuid::generate_uuid_v4();
108  msg1.actionType = "cancelOrder";
109  msg1.blockingType = "NONE";
110  msg1.actionDescription = "Hebe die Gabel der Weisheit";
111 
112 
113  msg2.actionId = uuid::generate_uuid_v4();
114  msg2.actionType = "Hupe";
115  msg2.blockingType = "NONE";
116  msg2.actionDescription = "Troet, Troet";
117 
118  param1.key = "orderId";
119  param1.value = "50";
120  param2.key = "Lautstaerke";
121  param2.value = "150dB";
122  msg1.actionParameters.push_back(param1);
123  msg2.actionParameters.push_back(param2);
124 
125  instAction.instantActions.push_back(msg1);
126  instAction.instantActions.push_back(msg2);
127 
128  pub->publish(instAction);
129  ROS_INFO_STREAM("New instant action sent!");
130 }
131 
132 int main(int argc, char **argv)
133 {
134  ros::init(argc, argv, "action_send_mockup");
135 
136  ros::NodeHandle nh;
137 
138  ros::Publisher actionPub = nh.advertise<vda5050_msgs::OrderActions>("orderAction", 1000);
139 
140  ros::Publisher instActionPub = nh.advertise<vda5050_msgs::InstantActions>("instantAction", 1000);
141 
142  ros::Publisher triggerPub = nh.advertise<std_msgs::String>("orderTrigger", 1000);
143 
144  int triggertrigger = -1;
145 
146  while (ros::ok())
147  {
148  if (triggertrigger == 0)
149  send_order_action(&actionPub, "79301da1-846d-44b0-b988-33957d157bd8");
150  else
151  send_order_action(&actionPub, "0");
152 
153  if(triggertrigger==3)
154  send_instant_action(&instActionPub);
155 
156  if(triggertrigger==5)
157  {
158  std_msgs::String msg;
159  msg.data = "79301da1-846d-44b0-b988-33957d157bd8";
160  triggerPub.publish(msg);
161  ROS_INFO_STREAM("Trigger sent!");
162  triggertrigger = -1;
163  }
164 
165  triggertrigger++;
166  ros::Rate r(0.5);
167  ros::spinOnce();
168  r.sleep();
169  }
170  return 0;
171 }
uuid::dis
static std::uniform_int_distribution dis(0, 15)
ros::Publisher
uuid::gen
static std::mt19937 gen(rd())
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
uuid::dis2
static std::uniform_int_distribution dis2(8, 11)
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
send_order_action
void send_order_action(ros::Publisher *pub, string ID)
Definition: action_msg_mockup.cpp:60
main
int main(int argc, char **argv)
Definition: action_msg_mockup.cpp:132
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::Rate::sleep
bool sleep()
uuid
Definition: action_msg_mockup.cpp:26
std
send_instant_action
void send_instant_action(ros::Publisher *pub)
Definition: action_msg_mockup.cpp:93
param
T param(const std::string &param_name, const T &default_val)
ros::Rate
uuid::generate_uuid_v4
std::string generate_uuid_v4()
Definition: action_msg_mockup.cpp:32
uuid::rd
static std::random_device rd
Definition: action_msg_mockup.cpp:27
ros::NodeHandle


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