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

#include <topic_info.hpp>

Inheritance diagram for topics_rviz_plugin::TopicInfo:
Inheritance graph
[legend]

Signals

void adjustLCDNumberOfDigits (const long unsigned number)
 

Public Member Functions

 TopicInfo (const std::string topic_name, const std::string topic_type)
 
virtual ~TopicInfo ()
 

Public Attributes

std::shared_ptr< QWidget > display_
 
std::shared_ptr< QLabel > label_
 
const std::string topic_name_
 
const std::string topic_type_
 

Protected Attributes

ros::NodeHandle nh_
 
ros::Subscriber sub_
 

Private Slots

void adjustLCDNumberOfDigitsHandler (const long unsigned number)
 

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 stringCallback (const std_msgs::StringConstPtr &msg)
 
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)
 

Detailed Description

Definition at line 26 of file topic_info.hpp.

Constructor & Destructor Documentation

topics_rviz_plugin::TopicInfo::TopicInfo ( const std::string  topic_name,
const std::string  topic_type 
)

Definition at line 6 of file topic_info.cpp.

topics_rviz_plugin::TopicInfo::~TopicInfo ( )
virtual

Definition at line 80 of file topic_info.cpp.

Member Function Documentation

void topics_rviz_plugin::TopicInfo::adjustLCDNumberOfDigits ( const long unsigned  number)
signal
void topics_rviz_plugin::TopicInfo::adjustLCDNumberOfDigitsHandler ( const long unsigned  number)
privateslot

Definition at line 86 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::boolCallback ( const std_msgs::BoolConstPtr &  msg)
private

Definition at line 105 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::durationCallback ( const std_msgs::DurationConstPtr &  msg)
private

Definition at line 115 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::float32Callback ( const std_msgs::Float32ConstPtr &  msg)
private

Definition at line 126 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::float64Callback ( const std_msgs::Float64ConstPtr &  msg)
private

Definition at line 134 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::int16Callback ( const std_msgs::Int16ConstPtr &  msg)
private

Definition at line 150 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::int32Callback ( const std_msgs::Int32ConstPtr &  msg)
private

Definition at line 158 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::int64Callback ( const std_msgs::Int64ConstPtr &  msg)
private

Definition at line 166 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::int8Callback ( const std_msgs::Int8ConstPtr &  msg)
private

Definition at line 142 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::stringCallback ( const std_msgs::StringConstPtr &  msg)
private

Definition at line 175 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::timeCallback ( const std_msgs::TimeConstPtr &  msg)
private

Definition at line 181 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::uint16Callback ( const std_msgs::UInt16ConstPtr &  msg)
private

Definition at line 196 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::uint32Callback ( const std_msgs::UInt32ConstPtr &  msg)
private

Definition at line 203 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::uint64Callback ( const std_msgs::UInt64ConstPtr &  msg)
private

Definition at line 211 of file topic_info.cpp.

void topics_rviz_plugin::TopicInfo::uint8Callback ( const std_msgs::UInt8ConstPtr &  msg)
private

Definition at line 189 of file topic_info.cpp.

Member Data Documentation

std::shared_ptr<QWidget> topics_rviz_plugin::TopicInfo::display_

Definition at line 39 of file topic_info.hpp.

std::shared_ptr<QLabel> topics_rviz_plugin::TopicInfo::label_

Definition at line 38 of file topic_info.hpp.

ros::NodeHandle topics_rviz_plugin::TopicInfo::nh_
protected

Definition at line 45 of file topic_info.hpp.

ros::Subscriber topics_rviz_plugin::TopicInfo::sub_
protected

Definition at line 46 of file topic_info.hpp.

const std::string topics_rviz_plugin::TopicInfo::topic_name_

Definition at line 36 of file topic_info.hpp.

const std::string topics_rviz_plugin::TopicInfo::topic_type_

Definition at line 37 of file topic_info.hpp.


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


topics_rviz_plugin
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 15:34:43