Signals | Public Member Functions | Public Attributes | Protected Slots | Private Member Functions | Private Attributes | List of all members
graph_rviz_plugin::TopicData Class Reference

#include <topic_data.hpp>

Inheritance diagram for graph_rviz_plugin::TopicData:
Inheritance graph
[legend]

Signals

void displayMessageBox (const QString, const QString, const QString, const QMessageBox::Icon)
 
void vectorUpdated (std::string topic_name)
 

Public Member Functions

void clearData ()
 
QVector< double > getTopicData ()
 
QVector< double > getTopicTime ()
 
void startRefreshData ()
 
void stopRefreshData ()
 
 TopicData (std::string topic_name, std::string topic_type, std::shared_ptr< ros::NodeHandle >, QObject *parent=nullptr)
 
 ~TopicData ()
 

Public Attributes

QColor color_ = Qt::GlobalColor::black
 
bool data_update_ = true
 
bool displayed_ = true
 
QCPGraph::LineStyle line_style_ = QCPGraph::lsLine
 
std::shared_ptr< ros::NodeHandlenh_
 
QCPScatterStyle::ScatterShape scatter_shape_ = QCPScatterStyle::ssCross
 
unsigned thickness_ = 1
 
QVector< double > topic_data_
 
const std::string topic_name_
 
QVector< double > topic_time_
 
const std::string topic_type_
 

Protected Slots

void displayMessageBoxHandler (const QString title, const QString text, const QString info="", const QMessageBox::Icon icon=QMessageBox::Icon::Information)
 

Private Member Functions

void boolCallback (const std_msgs::BoolConstPtr &msg)
 
void durationCallback (const std_msgs::DurationConstPtr &msg)
 
void float32Callback (const std_msgs::Float32ConstPtr &msg)
 
void float64Callback (const std_msgs::Float64ConstPtr &msg)
 
void int16Callback (const std_msgs::Int16ConstPtr &msg)
 
void int32Callback (const std_msgs::Int32ConstPtr &msg)
 
void int64Callback (const std_msgs::Int64ConstPtr &msg)
 
void int8Callback (const std_msgs::Int8ConstPtr &msg)
 
void pushData (const double Data, const ros::Time now)
 
void timeCallback (const std_msgs::TimeConstPtr &msg)
 
void uint16Callback (const std_msgs::UInt16ConstPtr &msg)
 
void uint32Callback (const std_msgs::UInt32ConstPtr &msg)
 
void uint64Callback (const std_msgs::UInt64ConstPtr &msg)
 
void uint8Callback (const std_msgs::UInt8ConstPtr &msg)
 

Private Attributes

ros::Time begin_
 
std::mutex data_mutex_
 
ros::Subscriber sub_
 

Detailed Description

Definition at line 32 of file topic_data.hpp.

Constructor & Destructor Documentation

◆ TopicData()

graph_rviz_plugin::TopicData::TopicData ( std::string  topic_name,
std::string  topic_type,
std::shared_ptr< ros::NodeHandle nh,
QObject *  parent = nullptr 
)

Definition at line 6 of file topic_data.cpp.

◆ ~TopicData()

graph_rviz_plugin::TopicData::~TopicData ( )

Definition at line 17 of file topic_data.cpp.

Member Function Documentation

◆ boolCallback()

void graph_rviz_plugin::TopicData::boolCallback ( const std_msgs::BoolConstPtr &  msg)
private

Definition at line 88 of file topic_data.cpp.

◆ clearData()

void graph_rviz_plugin::TopicData::clearData ( )

Definition at line 59 of file topic_data.cpp.

◆ 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

Definition at line 204 of file topic_data.cpp.

◆ durationCallback()

void graph_rviz_plugin::TopicData::durationCallback ( const std_msgs::DurationConstPtr &  msg)
private

Definition at line 96 of file topic_data.cpp.

◆ float32Callback()

void graph_rviz_plugin::TopicData::float32Callback ( const std_msgs::Float32ConstPtr &  msg)
private

Definition at line 104 of file topic_data.cpp.

◆ float64Callback()

void graph_rviz_plugin::TopicData::float64Callback ( const std_msgs::Float64ConstPtr &  msg)
private

Definition at line 112 of file topic_data.cpp.

◆ getTopicData()

QVector< double > graph_rviz_plugin::TopicData::getTopicData ( )

Definition at line 192 of file topic_data.cpp.

◆ getTopicTime()

QVector< double > graph_rviz_plugin::TopicData::getTopicTime ( )

Definition at line 198 of file topic_data.cpp.

◆ int16Callback()

void graph_rviz_plugin::TopicData::int16Callback ( const std_msgs::Int16ConstPtr &  msg)
private

Definition at line 128 of file topic_data.cpp.

◆ int32Callback()

void graph_rviz_plugin::TopicData::int32Callback ( const std_msgs::Int32ConstPtr &  msg)
private

Definition at line 136 of file topic_data.cpp.

◆ int64Callback()

void graph_rviz_plugin::TopicData::int64Callback ( const std_msgs::Int64ConstPtr &  msg)
private

Definition at line 144 of file topic_data.cpp.

◆ int8Callback()

void graph_rviz_plugin::TopicData::int8Callback ( const std_msgs::Int8ConstPtr &  msg)
private

Definition at line 120 of file topic_data.cpp.

◆ pushData()

void graph_rviz_plugin::TopicData::pushData ( const double  Data,
const ros::Time  now 
)
private

Definition at line 70 of file topic_data.cpp.

◆ startRefreshData()

void graph_rviz_plugin::TopicData::startRefreshData ( )

Definition at line 21 of file topic_data.cpp.

◆ stopRefreshData()

void graph_rviz_plugin::TopicData::stopRefreshData ( )

Definition at line 65 of file topic_data.cpp.

◆ timeCallback()

void graph_rviz_plugin::TopicData::timeCallback ( const std_msgs::TimeConstPtr &  msg)
private

Definition at line 152 of file topic_data.cpp.

◆ uint16Callback()

void graph_rviz_plugin::TopicData::uint16Callback ( const std_msgs::UInt16ConstPtr &  msg)
private

Definition at line 168 of file topic_data.cpp.

◆ uint32Callback()

void graph_rviz_plugin::TopicData::uint32Callback ( const std_msgs::UInt32ConstPtr &  msg)
private

Definition at line 176 of file topic_data.cpp.

◆ uint64Callback()

void graph_rviz_plugin::TopicData::uint64Callback ( const std_msgs::UInt64ConstPtr &  msg)
private

Definition at line 184 of file topic_data.cpp.

◆ uint8Callback()

void graph_rviz_plugin::TopicData::uint8Callback ( const std_msgs::UInt8ConstPtr &  msg)
private

Definition at line 160 of file topic_data.cpp.

◆ vectorUpdated

void graph_rviz_plugin::TopicData::vectorUpdated ( std::string  topic_name)
signal

Member Data Documentation

◆ begin_

ros::Time graph_rviz_plugin::TopicData::begin_
private

Definition at line 74 of file topic_data.hpp.

◆ color_

QColor graph_rviz_plugin::TopicData::color_ = Qt::GlobalColor::black

Definition at line 45 of file topic_data.hpp.

◆ data_mutex_

std::mutex graph_rviz_plugin::TopicData::data_mutex_
private

Definition at line 75 of file topic_data.hpp.

◆ data_update_

bool graph_rviz_plugin::TopicData::data_update_ = true

Definition at line 48 of file topic_data.hpp.

◆ displayed_

bool graph_rviz_plugin::TopicData::displayed_ = true

Definition at line 47 of file topic_data.hpp.

◆ line_style_

QCPGraph::LineStyle graph_rviz_plugin::TopicData::line_style_ = QCPGraph::lsLine

Definition at line 49 of file topic_data.hpp.

◆ nh_

std::shared_ptr<ros::NodeHandle> graph_rviz_plugin::TopicData::nh_

Definition at line 42 of file topic_data.hpp.

◆ scatter_shape_

QCPScatterStyle::ScatterShape graph_rviz_plugin::TopicData::scatter_shape_ = QCPScatterStyle::ssCross

Definition at line 50 of file topic_data.hpp.

◆ sub_

ros::Subscriber graph_rviz_plugin::TopicData::sub_
private

Definition at line 73 of file topic_data.hpp.

◆ thickness_

unsigned graph_rviz_plugin::TopicData::thickness_ = 1

Definition at line 46 of file topic_data.hpp.

◆ topic_data_

QVector<double> graph_rviz_plugin::TopicData::topic_data_

Definition at line 51 of file topic_data.hpp.

◆ topic_name_

const std::string graph_rviz_plugin::TopicData::topic_name_

Definition at line 43 of file topic_data.hpp.

◆ topic_time_

QVector<double> graph_rviz_plugin::TopicData::topic_time_

Definition at line 52 of file topic_data.hpp.

◆ topic_type_

const std::string graph_rviz_plugin::TopicData::topic_type_

Definition at line 44 of file topic_data.hpp.


The documentation for this class was generated from the following files:


graph_rviz_plugin
Author(s): Édouard Pronier, Victor Lamoine - Institut Maupertuis
autogenerated on Mon Feb 28 2022 22:27:31