#include <topic_data.hpp>
|
void | displayMessageBoxHandler (const QString title, const QString text, const QString info="", const QMessageBox::Icon icon=QMessageBox::Icon::Information) |
|
Definition at line 32 of file topic_data.hpp.
◆ TopicData()
graph_rviz_plugin::TopicData::TopicData |
( |
std::string |
topic_name, |
|
|
std::string |
topic_type, |
|
|
std::shared_ptr< ros::NodeHandle > |
nh, |
|
|
QObject * |
parent = nullptr |
|
) |
| |
◆ ~TopicData()
graph_rviz_plugin::TopicData::~TopicData |
( |
| ) |
|
◆ boolCallback()
void graph_rviz_plugin::TopicData::boolCallback |
( |
const std_msgs::BoolConstPtr & |
msg | ) |
|
|
private |
◆ clearData()
void graph_rviz_plugin::TopicData::clearData |
( |
| ) |
|
◆ displayMessageBox
void graph_rviz_plugin::TopicData::displayMessageBox |
( |
const QString |
, |
|
|
const QString |
, |
|
|
const QString |
, |
|
|
const QMessageBox::Icon |
|
|
) |
| |
|
signal |
◆ displayMessageBoxHandler
void graph_rviz_plugin::TopicData::displayMessageBoxHandler |
( |
const QString |
title, |
|
|
const QString |
text, |
|
|
const QString |
info = "" , |
|
|
const QMessageBox::Icon |
icon = QMessageBox::Icon::Information |
|
) |
| |
|
protectedslot |
◆ durationCallback()
void graph_rviz_plugin::TopicData::durationCallback |
( |
const std_msgs::DurationConstPtr & |
msg | ) |
|
|
private |
◆ float32Callback()
void graph_rviz_plugin::TopicData::float32Callback |
( |
const std_msgs::Float32ConstPtr & |
msg | ) |
|
|
private |
◆ float64Callback()
void graph_rviz_plugin::TopicData::float64Callback |
( |
const std_msgs::Float64ConstPtr & |
msg | ) |
|
|
private |
◆ getTopicData()
QVector< double > graph_rviz_plugin::TopicData::getTopicData |
( |
| ) |
|
◆ getTopicTime()
QVector< double > graph_rviz_plugin::TopicData::getTopicTime |
( |
| ) |
|
◆ int16Callback()
void graph_rviz_plugin::TopicData::int16Callback |
( |
const std_msgs::Int16ConstPtr & |
msg | ) |
|
|
private |
◆ int32Callback()
void graph_rviz_plugin::TopicData::int32Callback |
( |
const std_msgs::Int32ConstPtr & |
msg | ) |
|
|
private |
◆ int64Callback()
void graph_rviz_plugin::TopicData::int64Callback |
( |
const std_msgs::Int64ConstPtr & |
msg | ) |
|
|
private |
◆ int8Callback()
void graph_rviz_plugin::TopicData::int8Callback |
( |
const std_msgs::Int8ConstPtr & |
msg | ) |
|
|
private |
◆ pushData()
void graph_rviz_plugin::TopicData::pushData |
( |
const double |
Data, |
|
|
const ros::Time |
now |
|
) |
| |
|
private |
◆ startRefreshData()
void graph_rviz_plugin::TopicData::startRefreshData |
( |
| ) |
|
◆ stopRefreshData()
void graph_rviz_plugin::TopicData::stopRefreshData |
( |
| ) |
|
◆ timeCallback()
void graph_rviz_plugin::TopicData::timeCallback |
( |
const std_msgs::TimeConstPtr & |
msg | ) |
|
|
private |
◆ uint16Callback()
void graph_rviz_plugin::TopicData::uint16Callback |
( |
const std_msgs::UInt16ConstPtr & |
msg | ) |
|
|
private |
◆ uint32Callback()
void graph_rviz_plugin::TopicData::uint32Callback |
( |
const std_msgs::UInt32ConstPtr & |
msg | ) |
|
|
private |
◆ uint64Callback()
void graph_rviz_plugin::TopicData::uint64Callback |
( |
const std_msgs::UInt64ConstPtr & |
msg | ) |
|
|
private |
◆ uint8Callback()
void graph_rviz_plugin::TopicData::uint8Callback |
( |
const std_msgs::UInt8ConstPtr & |
msg | ) |
|
|
private |
◆ vectorUpdated
void graph_rviz_plugin::TopicData::vectorUpdated |
( |
std::string |
topic_name | ) |
|
|
signal |
◆ begin_
ros::Time graph_rviz_plugin::TopicData::begin_ |
|
private |
◆ color_
QColor graph_rviz_plugin::TopicData::color_ = Qt::GlobalColor::black |
◆ data_mutex_
std::mutex graph_rviz_plugin::TopicData::data_mutex_ |
|
private |
◆ data_update_
bool graph_rviz_plugin::TopicData::data_update_ = true |
◆ displayed_
bool graph_rviz_plugin::TopicData::displayed_ = true |
◆ line_style_
◆ nh_
◆ scatter_shape_
◆ sub_
◆ thickness_
unsigned graph_rviz_plugin::TopicData::thickness_ = 1 |
◆ topic_data_
QVector<double> graph_rviz_plugin::TopicData::topic_data_ |
◆ topic_name_
const std::string graph_rviz_plugin::TopicData::topic_name_ |
◆ topic_time_
QVector<double> graph_rviz_plugin::TopicData::topic_time_ |
◆ topic_type_
const std::string graph_rviz_plugin::TopicData::topic_type_ |
The documentation for this class was generated from the following files: