order_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 <iostream>
12 #include "vda5050_msgs/Order.h"
13 #include "vda5050_msgs/Node.h"
14 #include "vda5050_msgs/Edge.h"
15 #include "vda5050_msgs/NodePosition.h"
16 #include "vda5050_msgs/Action.h"
17 #include "vda5050_msgs/ActionParameter.h"
18 #include "vda5050_msgs/Trajectory.h"
19 #include "vda5050_msgs/ControlPoint.h"
20 #include "std_msgs/String.h"
21 #include <string>
22 #include <ctime>
23 #include <random>
24 
25 using namespace std;
26 
27 
28 string getTimestamp()
29 {
30  time_t now;
31  time(&now);
32  char buf[sizeof "2011-10-08T07:07:09Z"];
33  strftime(buf, sizeof buf, "%FT%TZ", gmtime(&now));
34  return(buf);
35 }
36 
37 namespace uuid {
38  static std::random_device rd;
39  static std::mt19937 gen(rd());
40  static std::uniform_int_distribution<> dis(0, 15);
41  static std::uniform_int_distribution<> dis2(8, 11);
42 
43  std::string generate_uuid_v4() {
44  std::stringstream ss;
45  int i;
46  ss << std::hex;
47  for (i = 0; i < 8; i++) {
48  ss << dis(gen);
49  }
50  ss << "-";
51  for (i = 0; i < 4; i++) {
52  ss << dis(gen);
53  }
54  ss << "-4";
55  for (i = 0; i < 3; i++) {
56  ss << dis(gen);
57  }
58  ss << "-";
59  ss << dis2(gen);
60  for (i = 0; i < 3; i++) {
61  ss << dis(gen);
62  }
63  ss << "-";
64  for (i = 0; i < 12; i++) {
65  ss << dis(gen);
66  };
67  return ss.str();
68  }
69 }
70 
71 /*
72  * This is a simple example program to demonstrate how to create a VDA 5050 msg in ROS
73  * This example creates the order message and implements all sub messages like Nodes, Edges and Actions
74  * In addition we show how Arrays in ROS messages can be implemented
75  *
76  */
77 
78 
79  // creates the NodePosition msg
80 vda5050_msgs::NodePosition createNodePosition()
81  {
82  vda5050_msgs::NodePosition nodePos;
83  nodePos.x=456.34;
84  nodePos.y=53.901;
85  nodePos.theta=43.4;
86  nodePos.mapId="hall 1";
87  nodePos.allowedDeviationXY=0.1;
88  nodePos.allowedDeviationTheta=3;
89  return (nodePos);
90  }
91 
92 //creates the actionParameter msg
93 vda5050_msgs::ActionParameter createActionParams()
94 {
95  vda5050_msgs::ActionParameter actionParam;
96  actionParam.key="load";
97  actionParam.value="KLTs";
98  return (actionParam);
99 }
100 
101 vda5050_msgs::Action createAction()
102 {
103  vda5050_msgs::Action action;
104  action.actionType="lift_fork";
105  action.actionId="";
106  action.actionDescription="drive to goal and stop there";
107  action.blockingType="HARD";
108  action.actionParameters.push_back(createActionParams());
109  return (action);
110 }
111 
112 //creates the node msg
113 vda5050_msgs::Node createNode()
114 {
115  vda5050_msgs::Node node;
116  node.nodeId="node_1";
117  node.sequenceId=753;
118  node.nodeDescription="test node";
119  node.released=false;
120  node.nodePosition=createNodePosition();
121  node.actions.push_back(createAction());
122  return (node);
123 }
124 
125 //creates the controlPoint msg
126 vda5050_msgs::ControlPoint createControlPoint()
127 {
128  vda5050_msgs::ControlPoint controlPoint;
129  controlPoint.x=4.2;
130  controlPoint.y=643.45;
131  controlPoint.orientation=-1.243;
132  controlPoint.weight=63.3;
133  return (controlPoint);
134 }
135 
136 //creates the trajectory msg
137 vda5050_msgs::Trajectory createTrajectory()
138 {
139  vda5050_msgs::Trajectory trajectory;
140  trajectory.degree=83;
141  trajectory.knotVector.push_back(47.2);
142  trajectory.controlPoints.push_back(createControlPoint());
143  return (trajectory);
144 }
145 
146 //creates the edge msg
147 vda5050_msgs::Edge createEdge()
148 {
149  vda5050_msgs::Edge edge;
150  edge.edgeId="edge_to_goal";
151  edge.sequenceId=5740;
152  edge.edgeDescription="edge between start and goal";
153  edge.released=true;
154  edge.startNodeId="init node";
155  edge.endNodeId="goal node";
156  edge.maxSpeed=10.4;
157  edge.maxHeight=1.2;
158  edge.minHeight=0.8;
159  edge.orientation=0.2;
160  edge.direction="right";
161  edge.rotationAllowed=true;
162  edge.maxRotationSpeed=0.2;
163  edge.trajectory=createTrajectory();
164  edge.length=645.1;
165  edge.actions.push_back(createAction());
166  return (edge);
167 }
168 
169 //creates the order msg
170 vda5050_msgs::Order createMessage()
171 {
172  vda5050_msgs::Order orderMsg;
173  orderMsg.headerId=1;
174  orderMsg.timestamp=getTimestamp();
175  orderMsg.version="1.1";
176  orderMsg.manufacturer="fml Enterprise";
177  orderMsg.serialNumber="ajf894ajc";
178  orderMsg.orderId="pass nr 3.5";
179  orderMsg.orderUpdateId=876324;
180  orderMsg.replace=false;
181  vda5050_msgs::Node node;
182  orderMsg.nodes.push_back(createNode());
183  orderMsg.edges.push_back(createEdge());
184  orderMsg.zoneSetId="fml hall of fame";
185  return (orderMsg);
186 
187 }
188 
189 int main(int argc, char **argv)
190 {
191  string topicPublishOrder = "orderTopic";
192  string topicPublishTrigger = "orderTrigger";
193  // if (argc > 1)
194  // topicPublishOrder=argv[1];
195  ros::init(argc, argv, "order_msg_test");
196  ros::NodeHandle nh;
197  ros::Rate loop_rate(1);
198  ros::Publisher publisherOrder = nh.advertise<vda5050_msgs::Order>(topicPublishOrder, 1000);
199  ros::Publisher publisherTrigger = nh.advertise<std_msgs::String>(topicPublishTrigger, 1000);
200  vda5050_msgs::Order msg = createMessage();
201  cout << topicPublishOrder << "\n" << topicPublishTrigger << "\n";
202  while(ros::ok())
203  {
204  static random_device rd;
205  static mt19937 gen(rd());
206  uniform_int_distribution<int> distribution(0,1);
207 
208  string newuuid = uuid::generate_uuid_v4();
209  std_msgs::String triggermsg;
210  triggermsg.data = newuuid;
211 
212  msg.nodes[0].actions[0].actionId = newuuid;
213  publisherOrder.publish(msg);
214  ros::spinOnce();
215  msg.headerId+=1;
216  if(distribution(gen))
217  publisherTrigger.publish(triggermsg);
218  loop_rate.sleep();
219  }
220  return(0);
221 };
createTrajectory
vda5050_msgs::Trajectory createTrajectory()
Definition: order_msg_mockup.cpp:137
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)
createMessage
vda5050_msgs::Order createMessage()
Definition: order_msg_mockup.cpp:170
ros.h
createControlPoint
vda5050_msgs::ControlPoint createControlPoint()
Definition: order_msg_mockup.cpp:126
createAction
vda5050_msgs::Action createAction()
Definition: order_msg_mockup.cpp:101
ros::spinOnce
ROSCPP_DECL void spinOnce()
createEdge
vda5050_msgs::Edge createEdge()
Definition: order_msg_mockup.cpp:147
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()
ros::Rate::sleep
bool sleep()
main
int main(int argc, char **argv)
Definition: order_msg_mockup.cpp:189
uuid
Definition: action_msg_mockup.cpp:26
std
createNodePosition
vda5050_msgs::NodePosition createNodePosition()
Definition: order_msg_mockup.cpp:80
ros::Rate
getTimestamp
string getTimestamp()
Definition: order_msg_mockup.cpp:28
createActionParams
vda5050_msgs::ActionParameter createActionParams()
Definition: order_msg_mockup.cpp:93
uuid::generate_uuid_v4
std::string generate_uuid_v4()
Definition: action_msg_mockup.cpp:32
createNode
vda5050_msgs::Node createNode()
Definition: order_msg_mockup.cpp:113
uuid::rd
static std::random_device rd
Definition: order_msg_mockup.cpp:38
ros::NodeHandle


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