AWViz-ROS C++ API Reference
|
Inherited plugin class to display ROS topics. More...
#include <display.hpp>
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. | |
Inherited plugin class to display ROS topics.
|
inline |
Construct an instance.
|
inlineoverride |
Destruct an instance.
|
inlineoverridevirtual |
End to display.
Implements awviz_common::Display.
|
inlineoverridevirtual |
Initialize the instance specifying the root ROS node and recording stream.
node | Root ROS node. |
stream | Recording stream. |
Implements awviz_common::Display.
|
inlineoverridevirtual |
Return true if the initialization is completed.
is_initialized_
. Reimplemented from awviz_common::Display.
|
protectedpure virtual |
Log subscribed ROS message to recording stream.
msg | Constant shared pointer of ROS message. |
|
inlineoverridevirtual |
Set status of attributes.
topic | Name of topic. |
entity | Entity path of the record. |
Implements awviz_common::Display.
|
inlineoverridevirtual |
Start to display.
Implements awviz_common::Display.
|
inlineprotectedvirtual |
Start to subscribing the specified topic.
rclcpp::SensorDataQoS
is used for QoS profile setting.
|
inlineprotectedvirtual |
End to subscribing the topic.
|
protected |
Topic property.
|
protected |
Subscription of the topic.
|
staticconstexprprotected |
Entity name of timeline record.