AWViz-ROS
Loading...
Searching...
No Matches
awviz_common::RosTopicDisplay< MsgType > Class Template Referenceabstract

Inherited plugin class to display ROS topics. More...

#include <display.hpp>

Inheritance diagram for awviz_common::RosTopicDisplay< MsgType >:
awviz_common::Display

Public Member Functions

 RosTopicDisplay ()
 Construct an instance.
 
 ~RosTopicDisplay () override
 Destruct an instance.
 
void initialize (rclcpp::Node::SharedPtr node, std::shared_ptr< rerun::RecordingStream > stream) override
 Initialize the instance specifying the root ROS node and recording stream.
 
void set_property (const std::string &topic, const std::shared_ptr< std::unordered_map< std::string, std::string > > entity_roots) override
 Set status of attributes.
 
void start () override
 Start to display.
 
void end () override
 End to display.
 
bool is_initialized () const override
 Return true if the initialization is completed.
 
- Public Member Functions inherited from awviz_common::Display
 Display ()=default
 
virtual ~Display ()=default
 
virtual void initialize (rclcpp::Node::SharedPtr node, std::shared_ptr< rerun::RecordingStream > stream)=0
 Initialize attributes.
 
virtual void set_property (const std::string &topic, const std::shared_ptr< std::unordered_map< std::string, std::string > > entity_roots)=0
 Set attributes of property.
 
virtual void start ()=0
 Start to display.
 
virtual void end ()=0
 End to display.
 
virtual bool is_initialized () const
 Return true if the initialization is completed.
 

Protected Member Functions

virtual void subscribe ()
 Start to subscribing the specified topic.
 
virtual void unsubscribe ()
 End to subscribing the topic.
 
virtual void log_message (typename MsgType::ConstSharedPtr msg)=0
 Log subscribed ROS message to recording stream.
 

Protected Attributes

rclcpp::Subscription< MsgType >::SharedPtr subscription_
 Subscription of the topic.
 
RosTopicProperty property_
 Topic property.
 
- Protected Attributes inherited from awviz_common::Display
rclcpp::Node::SharedPtr node_
 Node shared pointer.
 
std::shared_ptr< rerun::RecordingStream > stream_
 RecordingStream shared pointer.
 
bool is_initialized_
 Whether the object has been initialized.
 

Static Protected Attributes

static constexpr const char * TIMELINE_NAME = "timestamp"
 Entity name of timeline record.
 

Detailed Description

template<typename MsgType>
class awviz_common::RosTopicDisplay< MsgType >

Inherited plugin class to display ROS topics.

Constructor & Destructor Documentation

◆ RosTopicDisplay()

template<typename MsgType >
awviz_common::RosTopicDisplay< MsgType >::RosTopicDisplay ( )
inline

Construct an instance.

◆ ~RosTopicDisplay()

template<typename MsgType >
awviz_common::RosTopicDisplay< MsgType >::~RosTopicDisplay ( )
inlineoverride

Destruct an instance.

Member Function Documentation

◆ end()

template<typename MsgType >
void awviz_common::RosTopicDisplay< MsgType >::end ( )
inlineoverridevirtual

End to display.

Implements awviz_common::Display.

◆ initialize()

template<typename MsgType >
void awviz_common::RosTopicDisplay< MsgType >::initialize ( rclcpp::Node::SharedPtr  node,
std::shared_ptr< rerun::RecordingStream >  stream 
)
inlineoverridevirtual

Initialize the instance specifying the root ROS node and recording stream.

Parameters
nodeRoot ROS node.
streamRecording stream.

Implements awviz_common::Display.

◆ is_initialized()

template<typename MsgType >
bool awviz_common::RosTopicDisplay< MsgType >::is_initialized ( ) const
inlineoverridevirtual

Return true if the initialization is completed.

Returns
bool Return the value of the private member named is_initialized_.

Reimplemented from awviz_common::Display.

◆ log_message()

template<typename MsgType >
virtual void awviz_common::RosTopicDisplay< MsgType >::log_message ( typename MsgType::ConstSharedPtr  msg)
protectedpure virtual

Log subscribed ROS message to recording stream.

Parameters
msgConstant shared pointer of ROS message.
Note
Currently, if the corresponding entity path doesn't exist this just logs warning as text.

◆ set_property()

template<typename MsgType >
void awviz_common::RosTopicDisplay< MsgType >::set_property ( const std::string &  topic,
const std::shared_ptr< std::unordered_map< std::string, std::string > >  entity_roots 
)
inlineoverridevirtual

Set status of attributes.

Parameters
topicName of topic.
entityEntity path of the record.

Implements awviz_common::Display.

◆ start()

template<typename MsgType >
void awviz_common::RosTopicDisplay< MsgType >::start ( )
inlineoverridevirtual

Start to display.

Implements awviz_common::Display.

◆ subscribe()

template<typename MsgType >
virtual void awviz_common::RosTopicDisplay< MsgType >::subscribe ( )
inlineprotectedvirtual

Start to subscribing the specified topic.

Todo:
Currently, rclcpp::SensorDataQoS is used for QoS profile setting.

◆ unsubscribe()

template<typename MsgType >
virtual void awviz_common::RosTopicDisplay< MsgType >::unsubscribe ( )
inlineprotectedvirtual

End to subscribing the topic.

Member Data Documentation

◆ property_

template<typename MsgType >
RosTopicProperty awviz_common::RosTopicDisplay< MsgType >::property_
protected

Topic property.

◆ subscription_

template<typename MsgType >
rclcpp::Subscription<MsgType>::SharedPtr awviz_common::RosTopicDisplay< MsgType >::subscription_
protected

Subscription of the topic.

◆ TIMELINE_NAME

template<typename MsgType >
constexpr const char* awviz_common::RosTopicDisplay< MsgType >::TIMELINE_NAME = "timestamp"
staticconstexprprotected

Entity name of timeline record.


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