66 for(
const auto& elem : topicList)
68 ss<<
"/" << elem.second;
79 for(
const auto& elem : topicList)
84 else if (
CheckTopic(elem.first,
"orderUpdateId"))
90 else if (
CheckTopic(elem.first,
"lastNodeSequenceId"))
98 else if (
CheckTopic(elem.first,
"positionInitialized"))
100 else if (
CheckTopic(elem.first,
"localizationScore"))
102 else if (
CheckTopic(elem.first,
"deviationRange"))
108 else if (
CheckTopic(elem.first,
"mapDescription"))
118 else if (
CheckTopic(elem.first,
"newBaseRequest"))
120 else if (
CheckTopic(elem.first,
"distanceSinceLastNode"))
122 else if (
CheckTopic(elem.first,
"actionStates"))
124 else if (
CheckTopic(elem.first,
"batteryState"))
126 else if (
CheckTopic(elem.first,
"batteryCharge"))
128 else if (
CheckTopic(elem.first,
"batteryHealth"))
134 else if (
CheckTopic(elem.first,
"operatingMode"))
138 else if (
CheckTopic(elem.first,
"information"))
140 else if (
CheckTopic(elem.first,
"safetyState"))
144 else if (
CheckTopic(elem.first,
"fieldViolation"))
152 msg->pose.pose.orientation.x,
153 msg->pose.pose.orientation.y,
154 msg->pose.pose.orientation.z,
155 msg->pose.pose.orientation.w);
157 double roll, pitch, yaw;
158 m.getRPY(roll,pitch,yaw);
193 stateMessage.batteryState.batteryCharge=msg->percentage*100.0;
228 stateMessage.agvPosition.positionInitialized=msg->positionInitialized;
229 stateMessage.agvPosition.localizationScore=msg->localizationScore;
230 stateMessage.agvPosition.deviationRange=msg->deviationRange;
235 stateMessage.agvPosition.mapDescription=msg->mapDescription;
243 if (
CheckRange(0.0,1.0,msg->data,
"AGV Position Localization Score"))
290 stateMessage.batteryState.batteryHealth=msg->batteryHealth;
291 stateMessage.batteryState.batteryCharge=msg->batteryCharge;
292 stateMessage.batteryState.batteryVoltage=msg->batteryVoltage;
325 stateMessage.safetyState.fieldViolation=msg->fieldViolation;
338 int main(
int argc,
char **argv)