visualization_daemon.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 
11 #include <iostream>
12 #include <vector>
13 
14 /*
15  * TODO: publish to topicPub, if requirements are met
16  */
17 
18 VisDaemon::VisDaemon() : Daemon(&(this->nh), "visualization_daemon")
19 {
20 
21  LinkPublishTopics(&(this->nh));
22  LinkSubscriptionTopics(&(this->nh));
25 }
26 
28 {
30  return(passedTime >= updateInterval ? true:false);
31 }
32 
34 {
35  visMessage.headerId=GetHeader().headerId;
36  visMessage.timestamp=GetHeader().timestamp;
37  visMessage.version=GetHeader().version;
38  visMessage.manufacturer=GetHeader().manufacturer;
39  visMessage.serialNumber=GetHeader().serialNumber;
40  messagePublisher["/viz_to_mc"].publish(visMessage);
42 }
44 {
45  if (CheckPassedTime() == true)
46  {
48  }
49 }
51 {
52  std::map<std::string,std::string>topicList = GetTopicPublisherList();
53  std::stringstream ss;
55 
56  for(const auto& elem : topicList)
57  {
58  ss<< "/" << elem.second;
59  if (CheckTopic(elem.first,"visualization"))
60  {
61  messagePublisher[elem.second] =
62  nh->advertise<vda5050_msgs::Visualization>(ss.str(),1000);
63  }
64  }
65 }
66 
68 {
69  std::map<std::string,std::string>topicList=GetTopicSubscriberList();
70  for(const auto& elem : topicList)
71  {
72  if (CheckTopic(elem.first,"agvPosition"))
73  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::AGVPositionCallback, this);
74  else if (CheckTopic(elem.first,"positionInitialized"))
75  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::AGVPositionInitializedCallback, this);
76  else if (CheckTopic(elem.first,"localizationScore"))
77  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::AGVPositionLocalizationScoreCallback, this);
78  else if (CheckTopic(elem.first,"deviationRange"))
79  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::AGVPositionDeviationRangeCallback, this);
80  else if (CheckTopic(elem.first,"rosPose"))
81  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::ROSAGVPositionCallback, this);
82  else if (CheckTopic(elem.first,"mapId"))
83  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::AGVPositionMapIdCallback, this);
84  else if (CheckTopic(elem.first,"mapDescription"))
85  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::AGVPositionMapDescriptionCallback, this);
86  else if (CheckTopic(elem.first,"velocity"))
87  subscribers[elem.first]=nh->subscribe(elem.second,1000,&VisDaemon::ROSVelocityCallback, this);
88  }
89 }
90 
91 double VisDaemon::CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr& msg)
92 {
93  tf::Quaternion q(
94  msg->pose.pose.orientation.x,
95  msg->pose.pose.orientation.y,
96  msg->pose.pose.orientation.z,
97  msg->pose.pose.orientation.w);
98  tf::Matrix3x3 m(q);
99  double roll, pitch, yaw;
100  m.getRPY(roll,pitch,yaw);
101  return (yaw);
102 }
103 
104 //ROS specific callbacks
105 void VisDaemon::ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr& msg)
106 {
107  /* TODO: check if transformation is correct, e.g. missing rotation
108  * to transform ros to vda 5050 this might help:
109  * vda5050.x=ros.y*(-1)
110  * vda5050.y=ros.x
111  */
112  double theta;
113  visMessage.agvPosition.x=msg->pose.pose.position.x;
114  visMessage.agvPosition.y=msg->pose.pose.position.y;
115  theta=CalculateAgvOrientation(msg);
116  if (CheckRange(-M_PI,M_PI,theta,"theta"))
117  {
118  visMessage.agvPosition.theta=theta;
119  }
120 }
121 void VisDaemon::ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr& msg)
122 {
123  // local AGV based coordinate system ist the same as ros coordindat system, no transformation required
124  double omega;
125  visMessage.velocity.vx=msg->twist.twist.linear.x;
126  visMessage.velocity.vy=msg->twist.twist.linear.y;
127  if (CheckRange(-M_PI,M_PI,omega,"omega"))
128  {
129  visMessage.velocity.omega=msg->twist.twist.angular.z;
130  }
131 }
132 
133 void VisDaemon::AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr& msg)
134 {
135  visMessage.agvPosition.positionInitialized=msg->positionInitialized;
136  visMessage.agvPosition.localizationScore=msg->localizationScore;
137  visMessage.agvPosition.deviationRange=msg->deviationRange;
138  visMessage.agvPosition.x=msg->x;
139  visMessage.agvPosition.y=msg->y;
140  visMessage.agvPosition.theta=msg->theta;
141  visMessage.agvPosition.mapId=msg->mapId;
142  visMessage.agvPosition.mapDescription=msg->mapDescription;
143 }
144 void VisDaemon::AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr& msg)
145 {
146  visMessage.agvPosition.positionInitialized=msg->data;
147 }
148 void VisDaemon::AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr& msg)
149 {
150  if (CheckRange(0.0,1.0,msg->data,"AGV Position Localization Score"))
151  {
152  visMessage.agvPosition.localizationScore=msg->data;
153  }
154 }
155 void VisDaemon::AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr& msg)
156 {
157  visMessage.agvPosition.deviationRange=msg->data;
158 }
159 void VisDaemon::AGVPositionMapIdCallback(const std_msgs::String::ConstPtr& msg)
160 {
161  visMessage.agvPosition.mapId=msg->data;
162 }
163 void VisDaemon::AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr& msg)
164 {
165  visMessage.agvPosition.mapDescription=msg->data;
166 }
167 
168 int main(int argc, char **argv)
169 {
170  ros::init(argc, argv, "visualization_deamon");
171 
172  VisDaemon visDaemon;
173 
174  while(ros::ok())
175  {
176  visDaemon.UpdateVisualization();
177  ros::spinOnce();
178  }
179  return 0;
180 }
Daemon::GetHeader
vda5050_msgs::Header GetHeader()
Definition: src/daemon.cpp:106
Daemon::GetTopicPublisherList
std::map< std::string, std::string > GetTopicPublisherList()
Definition: src/daemon.cpp:46
VisDaemon::AGVPositionMapIdCallback
void AGVPositionMapIdCallback(const std_msgs::String::ConstPtr &msg)
Definition: visualization_daemon.cpp:159
visualization_daemon.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
VisDaemon::UpdateVisualization
void UpdateVisualization()
Definition: visualization_daemon.cpp:43
VisDaemon::lastUpdateTimestamp
ros::Time lastUpdateTimestamp
Definition: visualization_daemon.h:59
Daemon::subscribers
std::map< std::string, ros::Subscriber > subscribers
Definition: daemon.h:59
ros::spinOnce
ROSCPP_DECL void spinOnce()
VisDaemon::updateInterval
ros::Duration updateInterval
Definition: visualization_daemon.h:56
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
VisDaemon::LinkSubscriptionTopics
void LinkSubscriptionTopics(ros::NodeHandle *nh)
Definition: visualization_daemon.cpp:67
ros::ok
ROSCPP_DECL bool ok()
VisDaemon::AGVPositionInitializedCallback
void AGVPositionInitializedCallback(const std_msgs::Bool::ConstPtr &msg)
Definition: visualization_daemon.cpp:144
Daemon::getTopicStructurePrefix
std::string getTopicStructurePrefix()
Definition: src/daemon.cpp:95
VisDaemon::PublishVisualization
void PublishVisualization()
Definition: visualization_daemon.cpp:33
VisDaemon::VisDaemon
VisDaemon()
Definition: visualization_daemon.cpp:18
Daemon::GetTopicSubscriberList
std::map< std::string, std::string > GetTopicSubscriberList()
Definition: src/daemon.cpp:51
Daemon::CheckRange
bool CheckRange(double lowerRange, double upperRange, double value, std::string msg_name)
Definition: src/daemon.cpp:134
VisDaemon::AGVPositionCallback
void AGVPositionCallback(const vda5050_msgs::AGVPosition::ConstPtr &msg)
Definition: visualization_daemon.cpp:133
VisDaemon::AGVPositionDeviationRangeCallback
void AGVPositionDeviationRangeCallback(const std_msgs::Float64::ConstPtr &msg)
Definition: visualization_daemon.cpp:155
VisDaemon::AGVPositionMapDescriptionCallback
void AGVPositionMapDescriptionCallback(const std_msgs::String::ConstPtr &msg)
Definition: visualization_daemon.cpp:163
VisDaemon
Definition: visualization_daemon.h:46
Daemon::messagePublisher
std::map< std::string, ros::Publisher > messagePublisher
Definition: daemon.h:54
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Daemon::nh
ros::NodeHandle nh
Definition: daemon.h:67
Daemon
Definition: daemon.h:29
VisDaemon::ROSAGVPositionCallback
void ROSAGVPositionCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: visualization_daemon.cpp:105
main
int main(int argc, char **argv)
Definition: visualization_daemon.cpp:168
VisDaemon::ROSVelocityCallback
void ROSVelocityCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: visualization_daemon.cpp:121
VisDaemon::visMessage
vda5050_msgs::Visualization visMessage
Definition: visualization_daemon.h:49
VisDaemon::AGVPositionLocalizationScoreCallback
void AGVPositionLocalizationScoreCallback(const std_msgs::Float64::ConstPtr &msg)
Definition: visualization_daemon.cpp:148
VisDaemon::LinkPublishTopics
void LinkPublishTopics(ros::NodeHandle *nh)
Definition: visualization_daemon.cpp:50
VisDaemon::CheckPassedTime
bool CheckPassedTime()
Definition: visualization_daemon.cpp:27
ros::Duration
VisDaemon::CalculateAgvOrientation
double CalculateAgvOrientation(const nav_msgs::Odometry::ConstPtr &msg)
Definition: visualization_daemon.cpp:91
ros::NodeHandle
Daemon::CheckTopic
bool CheckTopic(std::string str1, std::string str2)
Definition: src/daemon.cpp:117
ros::Time::now
static Time now()


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