12 #include "vda5050_msgs/State.h"
13 #include "vda5050_msgs/AGVPosition.h"
25 char buf[
sizeof "2011-10-08T07:07:09Z"];
26 strftime(buf,
sizeof buf,
"%FT%TZ", gmtime(&now));
37 vda5050_msgs::State msg;
38 msg.header.headerId=1;
40 msg.header.version=
"1.1";
41 msg.header.manufacturer=
"fml Enterprise";
42 msg.header.serialNumber=
"ajf894ajc";
46 msg.agvPosition.x=25.07;
47 msg.agvPosition.y=17.44;
48 msg.agvPosition.theta=0;
49 msg.agvPosition.positionInitialized=
true;
50 msg.agvPosition.mapId=
"c01bf928-27b4-4018-9df0-cb37b96bf710";
51 msg.batteryState.batteryCharge=70.0;
58 vda5050_msgs::State
updateMessage(vda5050_msgs::State msg,
float angle,
float r,
float mx,
float my)
61 msg.agvPosition.x=r*cos(angle)+mx;
62 msg.agvPosition.y=r*sin(angle)+my;
63 msg.agvPosition.theta=angle;
67 int main(
int argc,
char **argv)
69 string topicPublish =
"state";
70 string topicViz=
"viz";
73 ros::init(argc, argv,
"state_msg_mockup");
81 cout << topicPublish <<
"\n";
88 msg.header.headerId+=1;