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"
32 char buf[
sizeof "2011-10-08T07:07:09Z"];
33 strftime(buf,
sizeof buf,
"%FT%TZ", gmtime(&now));
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);
47 for (i = 0; i < 8; i++) {
51 for (i = 0; i < 4; i++) {
55 for (i = 0; i < 3; i++) {
60 for (i = 0; i < 3; i++) {
64 for (i = 0; i < 12; i++) {
82 vda5050_msgs::NodePosition nodePos;
86 nodePos.mapId=
"hall 1";
87 nodePos.allowedDeviationXY=0.1;
88 nodePos.allowedDeviationTheta=3;
95 vda5050_msgs::ActionParameter actionParam;
96 actionParam.key=
"load";
97 actionParam.value=
"KLTs";
103 vda5050_msgs::Action action;
104 action.actionType=
"lift_fork";
106 action.actionDescription=
"drive to goal and stop there";
107 action.blockingType=
"HARD";
115 vda5050_msgs::Node node;
116 node.nodeId=
"node_1";
118 node.nodeDescription=
"test node";
128 vda5050_msgs::ControlPoint controlPoint;
130 controlPoint.y=643.45;
131 controlPoint.orientation=-1.243;
132 controlPoint.weight=63.3;
133 return (controlPoint);
139 vda5050_msgs::Trajectory trajectory;
140 trajectory.degree=83;
141 trajectory.knotVector.push_back(47.2);
149 vda5050_msgs::Edge edge;
150 edge.edgeId=
"edge_to_goal";
151 edge.sequenceId=5740;
152 edge.edgeDescription=
"edge between start and goal";
154 edge.startNodeId=
"init node";
155 edge.endNodeId=
"goal node";
159 edge.orientation=0.2;
160 edge.direction=
"right";
161 edge.rotationAllowed=
true;
162 edge.maxRotationSpeed=0.2;
172 vda5050_msgs::Order orderMsg;
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;
184 orderMsg.zoneSetId=
"fml hall of fame";
189 int main(
int argc,
char **argv)
191 string topicPublishOrder =
"orderTopic";
192 string topicPublishTrigger =
"orderTrigger";
201 cout << topicPublishOrder <<
"\n" << topicPublishTrigger <<
"\n";
204 static random_device
rd;
205 static mt19937
gen(
rd());
206 uniform_int_distribution<int> distribution(0,1);
209 std_msgs::String triggermsg;
210 triggermsg.data = newuuid;
212 msg.nodes[0].actions[0].actionId = newuuid;
216 if(distribution(
gen))
217 publisherTrigger.publish(triggermsg);