state_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/State.h"
13 #include "vda5050_msgs/AGVPosition.h"
14 #include <string>
15 #include <ctime>
16 #include <math.h>
17 
18 using namespace std;
19 
20 
21 string getTimestamp()
22 {
23  time_t now;
24  time(&now);
25  char buf[sizeof "2011-10-08T07:07:09Z"];
26  strftime(buf, sizeof buf, "%FT%TZ", gmtime(&now));
27  return(buf);
28 }
29 
30 /*
31  * This is a simple example program to send a state mockup file to anyfleet
32  */
33 
34 //creates the order msg
35 vda5050_msgs::State createMessage()
36 {
37  vda5050_msgs::State msg;
38  msg.header.headerId=1;
39  msg.header.timestamp=getTimestamp();
40  msg.header.version="1.1";
41  msg.header.manufacturer="fml Enterprise";
42  msg.header.serialNumber="ajf894ajc";
43 // msg.orderId="pass nr 3.5";
44 // msg.orderUpdateId=876324;
45 // msg.zoneSetId="fml hall of fame";
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;
52 // msg.driving=true;
53 
54  return (msg);
55 
56 }
57 
58 vda5050_msgs::State updateMessage(vda5050_msgs::State msg, float angle, float r, float mx, float my)
59 {
60 
61  msg.agvPosition.x=r*cos(angle)+mx;
62  msg.agvPosition.y=r*sin(angle)+my;
63  msg.agvPosition.theta=angle;
64  return (msg);
65 }
66 
67 int main(int argc, char **argv)
68 {
69  string topicPublish = "state";
70  string topicViz="viz";
71  if (argc > 1)
72  topicPublish=argv[1];
73  ros::init(argc, argv, "state_msg_mockup");
74  ros::NodeHandle nh;
75  ros::Rate loop_rate(10);
76  ros::Publisher publisherState = nh.advertise<vda5050_msgs::State>(topicPublish, 1000);
77  vda5050_msgs::State msg = createMessage();
78  float mx=30;
79  float my=30;
80  float r=10;
81  cout << topicPublish << "\n";
82  float angle=-M_PI;
83  while(ros::ok())
84  {
85  publisherState.publish(msg);
86  ros::spinOnce();
87  loop_rate.sleep();
88  msg.header.headerId+=1;
89 // msg=updateMessage(msg,angle,r,mx,my);
90 // angle+=0.05;
91 // if (angle >= M_PI)
92 // angle=-M_PI;
93  }
94  return(0);
95 };
96 
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
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()
getTimestamp
string getTimestamp()
Definition: state_mockup.cpp:21
updateMessage
vda5050_msgs::State updateMessage(vda5050_msgs::State msg, float angle, float r, float mx, float my)
Definition: state_mockup.cpp:58
createMessage
vda5050_msgs::State createMessage()
Definition: state_mockup.cpp:35
main
int main(int argc, char **argv)
Definition: state_mockup.cpp:67
ros::Rate::sleep
bool sleep()
std
ros::Rate
ros::NodeHandle


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