1 #ifndef GRAPH_RVIZ_PLUGIN_TOPIC_DATA_HPP 2 #define GRAPH_RVIZ_PLUGIN_TOPIC_DATA_HPP 13 #include <sensor_msgs/Image.h> 14 #include <std_msgs/Bool.h> 15 #include <std_msgs/Duration.h> 16 #include <std_msgs/Float32.h> 17 #include <std_msgs/Float64.h> 18 #include <std_msgs/Int16.h> 19 #include <std_msgs/Int32.h> 20 #include <std_msgs/Int64.h> 21 #include <std_msgs/Int8.h> 22 #include <std_msgs/String.h> 23 #include <std_msgs/Time.h> 24 #include <std_msgs/UInt16.h> 25 #include <std_msgs/UInt32.h> 26 #include <std_msgs/UInt64.h> 27 #include <std_msgs/UInt8.h> 37 std::string topic_type,
38 std::shared_ptr<ros::NodeHandle>,
39 QObject *parent =
nullptr);
42 std::shared_ptr<ros::NodeHandle>
nh_;
45 QColor
color_ = Qt::GlobalColor::black;
64 const QMessageBox::Icon);
69 const QString info =
"",
70 const QMessageBox::Icon icon = QMessageBox::Icon::Information);
void int16Callback(const std_msgs::Int16ConstPtr &msg)
void uint32Callback(const std_msgs::UInt32ConstPtr &msg)
void durationCallback(const std_msgs::DurationConstPtr &msg)
QCPScatterStyle::ScatterShape scatter_shape_
void uint16Callback(const std_msgs::UInt16ConstPtr &msg)
std::shared_ptr< ros::NodeHandle > nh_
QCPGraph::LineStyle line_style_
QVector< double > topic_time_
void vectorUpdated(std::string topic_name)
QVector< double > getTopicData()
void uint8Callback(const std_msgs::UInt8ConstPtr &msg)
TopicData(std::string topic_name, std::string topic_type, std::shared_ptr< ros::NodeHandle >, QObject *parent=nullptr)
void pushData(const double Data, const ros::Time now)
const std::string topic_name_
QVector< double > getTopicTime()
void timeCallback(const std_msgs::TimeConstPtr &msg)
void float32Callback(const std_msgs::Float32ConstPtr &msg)
QVector< double > topic_data_
void boolCallback(const std_msgs::BoolConstPtr &msg)
const std::string topic_type_
void float64Callback(const std_msgs::Float64ConstPtr &msg)
void int8Callback(const std_msgs::Int8ConstPtr &msg)
void uint64Callback(const std_msgs::UInt64ConstPtr &msg)
void displayMessageBoxHandler(const QString title, const QString text, const QString info="", const QMessageBox::Icon icon=QMessageBox::Icon::Information)
void int64Callback(const std_msgs::Int64ConstPtr &msg)
data points are connected by a straight line
void displayMessageBox(const QString, const QString, const QString, const QMessageBox::Icon)
void int32Callback(const std_msgs::Int32ConstPtr &msg)