14 #include "boost/date_time/posix_time/posix_time.hpp" 16 #include "std_msgs/String.h" 17 #include "vda5050_msgs/Header.h" 22 #define DEFAULT_ERROR_TOPIC "/internal_errors" 129 std::map<std::string,std::string> topicList);
166 bool CheckTopic(std::string str1,std::string str2);
171 std::string
GetTopic(std::string hierarchical_topic);
212 std::string paramTopicName);
229 bool CheckRange(
double lowerRange,
double upperRange,
double value,
230 std::string msg_name);
void createTopicStructurePrefix()
std::vector< std::string > GetMsgList(std::map< std::string, std::string > topicList)
std::map< std::string, ros::Publisher > messagePublisher
std::string mqttTopicStructurePrefix
std::map< std::string, std::string > GetTopicPublisherList()
bool CheckRange(double lowerRange, double upperRange, double value, std::string msg_name)
std::string getTopicStructurePrefix()
std::string GetTopic(std::string hierarchical_topic)
std::map< std::string, std::string > ReadTopicParams(ros::NodeHandle *nh, std::string paramTopicName)
std::map< std::string, std::string > topicSubscriberList
bool CompareStrings(std::string str1, std::string str2)
vda5050_msgs::Header GetHeader()
std::map< std::string, std::string > topicPublisherList
bool CheckTopic(std::string str1, std::string str2)
ros::Publisher errorPublisher
std::string GetParameter(std::string param)
std::map< std::string, ros::Subscriber > subscribers
void LinkErrorTopics(ros::NodeHandle *nh)
std::string CreateTimestamp()
std::map< std::string, std::string > GetTopicSubscriberList()
vda5050_msgs::Header messageHeader