1 #ifndef TOPICS_RVIZ_PLUGIN_TOPIC_INFO_HPP 2 #define TOPICS_RVIZ_PLUGIN_TOPIC_INFO_HPP 8 #include <std_msgs/Bool.h> 9 #include <std_msgs/Duration.h> 10 #include <std_msgs/Int8.h> 11 #include <std_msgs/Int16.h> 12 #include <std_msgs/Int32.h> 13 #include <std_msgs/Int64.h> 14 #include <std_msgs/Time.h> 15 #include <std_msgs/UInt8.h> 16 #include <std_msgs/UInt16.h> 17 #include <std_msgs/UInt32.h> 18 #include <std_msgs/UInt64.h> 19 #include <std_msgs/String.h> 20 #include <std_msgs/Float32.h> 21 #include <std_msgs/Float64.h> 32 const std::string topic_type);
void uint64Callback(const std_msgs::UInt64ConstPtr &msg)
void int8Callback(const std_msgs::Int8ConstPtr &msg)
void adjustLCDNumberOfDigitsHandler(const long unsigned number)
const std::string topic_type_
void float32Callback(const std_msgs::Float32ConstPtr &msg)
void durationCallback(const std_msgs::DurationConstPtr &msg)
void stringCallback(const std_msgs::StringConstPtr &msg)
void float64Callback(const std_msgs::Float64ConstPtr &msg)
const std::string topic_name_
void timeCallback(const std_msgs::TimeConstPtr &msg)
std::shared_ptr< QLabel > label_
void int16Callback(const std_msgs::Int16ConstPtr &msg)
std::shared_ptr< QWidget > display_
void uint8Callback(const std_msgs::UInt8ConstPtr &msg)
TopicInfo(const std::string topic_name, const std::string topic_type)
void uint32Callback(const std_msgs::UInt32ConstPtr &msg)
void int64Callback(const std_msgs::Int64ConstPtr &msg)
void int32Callback(const std_msgs::Int32ConstPtr &msg)
void uint16Callback(const std_msgs::UInt16ConstPtr &msg)
void adjustLCDNumberOfDigits(const long unsigned number)
void boolCallback(const std_msgs::BoolConstPtr &msg)