AWViz-ROS C++ API Reference
|
Intermediate class for display items. More...
#include <display.hpp>
Public Member Functions | |
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 Attributes | |
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. | |
Intermediate class for display items.
|
default |
|
virtualdefault |
|
pure virtual |
End to display.
Implemented in awviz_common::RosTopicDisplay< MsgType >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CameraInfo >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CompressedImage >, awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::DetectedObjects >, awviz_common::RosTopicDisplay< sensor_msgs::msg::Image >, awviz_common::RosTopicDisplay< sensor_msgs::msg::PointCloud2 >, and awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::TrackedObjects >.
|
pure virtual |
Initialize attributes.
node | ROS node instance. |
stream | Recording stream. |
Implemented in awviz_common::RosTopicDisplay< MsgType >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CameraInfo >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CompressedImage >, awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::DetectedObjects >, awviz_common::RosTopicDisplay< sensor_msgs::msg::Image >, awviz_common::RosTopicDisplay< sensor_msgs::msg::PointCloud2 >, and awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::TrackedObjects >.
|
inlinevirtual |
Return true if the initialization is completed.
is_initialized_
. Reimplemented in awviz_common::RosTopicDisplay< MsgType >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CameraInfo >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CompressedImage >, awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::DetectedObjects >, awviz_common::RosTopicDisplay< sensor_msgs::msg::Image >, awviz_common::RosTopicDisplay< sensor_msgs::msg::PointCloud2 >, and awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::TrackedObjects >.
|
pure virtual |
Set attributes of property.
topic | Name of topic. |
entity | Entity path of the record. |
Implemented in awviz_common::RosTopicDisplay< MsgType >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CameraInfo >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CompressedImage >, awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::DetectedObjects >, awviz_common::RosTopicDisplay< sensor_msgs::msg::Image >, awviz_common::RosTopicDisplay< sensor_msgs::msg::PointCloud2 >, and awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::TrackedObjects >.
|
pure virtual |
Start to display.
Implemented in awviz_common::RosTopicDisplay< MsgType >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CameraInfo >, awviz_common::RosTopicDisplay< sensor_msgs::msg::CompressedImage >, awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::DetectedObjects >, awviz_common::RosTopicDisplay< sensor_msgs::msg::Image >, awviz_common::RosTopicDisplay< sensor_msgs::msg::PointCloud2 >, and awviz_common::RosTopicDisplay< autoware_perception_msgs::msg::TrackedObjects >.
|
protected |
Whether the object has been initialized.
|
protected |
Node shared pointer.
|
protected |
RecordingStream shared pointer.