12 OrderMsg::OrderMsg(vda5050_msgs::Order &msg,
int last_released_node, std::string& last_released_nodeId)
27 this->
_msg.nodes = std::vector<vda5050_msgs::Node>{};
29 for (
int i = 0; i < node_num; i++)
31 vda5050_msgs::Node subnode;
38 std::string rand_nodeId_str = this->
rand_str(36);
40 subnode.nodeId = rand_nodeId_str;
44 subnode.nodeDescription =
"Node based on device state: Header: 135";
46 if (i < node_released_num)
48 subnode.released =
true;
49 if (i == node_released_num - 1)
56 subnode.released =
false;
59 subnode.nodePosition.x = 10.0+5*i;
60 subnode.nodePosition.y = 10.0+5*i;
61 subnode.nodePosition.theta = 0.0;
62 subnode.nodePosition.allowedDeviationXY = 100.0;
63 subnode.nodePosition.allowedDeviationTheta = 100.0;
64 subnode.nodePosition.mapId =
"6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
65 subnode.nodePosition.mapDescription =
"Id: 6d673fe4-8660-4dec-9b06-8d2b6e4ee8d2";
67 std::vector<vda5050_msgs::Action> action_list;
69 action_list.push_back(action);
70 subnode.actions = action_list;
72 this->
_msg.nodes.push_back(subnode);
79 this->
_msg.edges = std::vector<vda5050_msgs::Edge>{};
81 for (
int i = 0; i < (node_num - 1); i++)
83 vda5050_msgs::Edge subedge;
85 std::string rand_edgeId_str = this->
rand_str(36);
86 subedge.edgeId = rand_edgeId_str;
90 subedge.edgeDescription =
"Edge connecting 9b5d075a-8757-4002-929d-e245c624881b to 6f61c844-e3d7-4018-85bf-c9d867fdd3d4";
92 if (i < (node_released_num - 1))
94 subedge.released =
true;
98 subedge.released =
false;
102 subedge.startNodeId = this->
_msg.nodes[i].nodeId;
104 subedge.endNodeId = this->
_msg.nodes[i + 1].nodeId;
105 subedge.maxSpeed = 0.0;
106 subedge.maxHeight = 0.0;
107 subedge.minHeight = 0.0;
108 subedge.orientation = 0.0;
109 subedge.direction =
" ";
110 subedge.rotationAllowed =
false;
111 subedge.maxRotationSpeed = 0.0;
112 subedge.trajectory.degree = 0.0;
113 subedge.trajectory.knotVector = std::vector<_Float64>{};
114 subedge.trajectory.controlPoints = std::vector<vda5050_msgs::ControlPoint>{};
115 subedge.length = 0.0;
116 subedge.actions = std::vector<vda5050_msgs::Action>{};
118 subedge.actions.push_back(action);
120 this->
_msg.edges.push_back(subedge);
126 vda5050_msgs::Action action;
127 action.actionType = actionType;
129 std::string rand_actionId_str = this->
rand_str(36);
130 action.actionId = rand_actionId_str;
131 action.actionDescription = actionType;
132 action.blockingType =
"NONE";
133 action.actionParameters = std::vector<vda5050_msgs::ActionParameter>{};
135 vda5050_msgs::ActionParameter actionParameter;
136 actionParameter.key =
"waitFor";
137 actionParameter.value =
"1";
139 action.actionParameters.push_back(actionParameter);
145 std::string new_orderId,
146 int new_oderUpdateId,
148 int node_released_num)
151 this->
_msg.headerId = new_headerId;
152 this->
_msg.timestamp =
"10/6/2022 10:16:37 AM";
153 this->
_msg.version =
"v1";
154 this->
_msg.manufacturer;
155 this->
_msg.serialNumber;
159 this->
_msg.orderId = new_orderId;
160 this->
_msg.orderUpdateId = new_oderUpdateId;
162 this->
_msg.zoneSetId =
" ";
178 for (idx = 0; idx < len; idx++)
180 c =
'a' + rand() % 26;