Class DepthCloudDisplay
Defined in File depth_cloud_display.hpp
Inheritance Relationships
Base Type
public rviz_common::Display
Class Documentation
-
class DepthCloudDisplay : public rviz_common::Display
Public Functions
-
DepthCloudDisplay()
-
~DepthCloudDisplay() override
-
void onInitialize() override
-
void update(float wall_dt, float ros_dt) override
-
void reset() override
-
void setTopic(const QString &topic, const QString &datatype) override
Protected Types
-
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::Image> SyncPolicyDepthColor
-
typedef message_filters::Synchronizer<SyncPolicyDepthColor> SynchronizerDepthColor
Protected Functions
-
void scanForTransportSubscriberPlugins()
-
void onEnable() override
-
void onDisable() override
-
void fixedFrameChanged() override
-
void subscribe()
-
void unsubscribe()
-
void clear()
-
void updateStatus(rviz_common::properties::StatusProperty::Level level, const QString &name, const QString &text)
-
void setStatusList()
Protected Attributes
-
uint32_t messages_received_
-
std::unique_ptr<image_transport::ImageTransport> depthmap_it_
-
std::shared_ptr<image_transport::SubscriberFilter> depthmap_sub_
-
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::Image, rviz_common::transformation::FrameTransformer>> depthmap_tf_filter_
-
std::unique_ptr<image_transport::ImageTransport> rgb_it_
-
std::shared_ptr<image_transport::SubscriberFilter> rgb_sub_
-
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr cam_info_sub_
-
sensor_msgs::msg::CameraInfo::ConstSharedPtr cam_info_
-
std::mutex cam_info_mutex_
-
std::shared_ptr<SynchronizerDepthColor> sync_depth_color_
-
rclcpp::Time subscription_start_time_
-
rviz_common::properties::EditableEnumProperty *reliability_policy_property_
-
rmw_qos_profile_t qos_profile_
-
rviz_common::properties::Property *topic_filter_property_
-
rviz_common::properties::IntProperty *queue_size_property_
-
rviz_common::properties::BoolProperty *use_auto_size_property_
-
rviz_common::properties::FloatProperty *auto_size_factor_property_
-
rviz_common::properties::RosFilteredTopicProperty *depth_topic_property_
-
rviz_common::properties::EnumProperty *depth_transport_property_
-
rviz_common::properties::RosFilteredTopicProperty *color_topic_property_
-
rviz_common::properties::EnumProperty *color_transport_property_
-
rviz_common::properties::BoolProperty *use_occlusion_compensation_property_
-
rviz_common::properties::FloatProperty *occlusion_shadow_timeout_property_
-
uint32_t queue_size_
-
std::unique_ptr<rviz_common::MultiLayerDepth> ml_depth_data_
-
Ogre::Quaternion current_orientation_
-
Ogre::Vector3 current_position_
-
float angular_thres_
-
float trans_thres_
-
std::unique_ptr<PointCloudCommon> pointcloud_common_
-
std::set<std::string> transport_plugin_types_
Protected Slots
-
void updateQueueSize()
-
void fillTransportOptionList(rviz_common::properties::EnumProperty *property)
Fill list of available and working transport options.
-
void transformerChangedCallback()
-
void updateQosProfile()
-
virtual void updateTopic()
-
virtual void updateTopicFilter()
-
virtual void updateUseAutoSize()
-
virtual void updateAutoSizeFactor()
-
virtual void updateUseOcclusionCompensation()
-
virtual void updateOcclusionTimeOut()
-
DepthCloudDisplay()