Go to the documentation of this file.
30 #ifndef RVIZ_DEPTH_CLOUD_DISPLAY_H
31 #define RVIZ_DEPTH_CLOUD_DISPLAY_H
34 #include <boost/shared_ptr.hpp>
35 #include <boost/thread/mutex.hpp>
57 #include <QtCore/QRegularExpression>
65 class SubscriberFilter;
75 class MultiLayerDepth;
82 const QString& default_value = QString(),
83 const QString& message_type = QString(),
84 const QString& description = QString(),
85 const QRegularExpression& filter = QRegularExpression(),
89 , filter_enabled_(true)
93 template <
typename Func,
typename R>
95 const QString& default_value,
96 const QString& message_type,
97 const QString& description,
98 const QRegularExpression& filter,
104 connect(receiver, std::forward<Func>(changed_slot));
108 template <
typename Func,
typename P>
110 const QString& default_value,
111 const QString& message_type,
112 const QString& description,
113 const QRegularExpression& filter,
118 connect(parent, std::forward<Func>(changed_slot));
124 filter_enabled_ = enabled;
136 QStringList filtered_strings_;
139 RosTopicProperty::fillTopicList();
142 strings_ = strings_.filter(filter_);
161 void onInitialize()
override;
164 void update(
float wall_dt,
float ros_dt)
override;
165 void reset()
override;
166 void setTopic(
const QString& topic,
const QString&
datatype)
override;
169 void updateQueueSize();
174 virtual void updateTopic();
175 virtual void updateTopicFilter();
176 virtual void updateUseAutoSize();
177 virtual void updateAutoSizeFactor();
178 virtual void updateUseOcclusionCompensation();
179 virtual void updateOcclusionTimeOut();
182 void scanForTransportSubscriberPlugins();
184 typedef std::vector<rviz::PointCloud::Point>
V_Point;
186 virtual void processMessage(
const sensor_msgs::Image::ConstPtr& msg);
187 virtual void processMessage(
const sensor_msgs::ImageConstPtr& depth_msg,
188 const sensor_msgs::ImageConstPtr& rgb_msg);
189 void caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg);
192 void onEnable()
override;
193 void onDisable()
override;
195 void fixedFrameChanged()
override;
207 void setStatusList();
215 boost::scoped_ptr<image_transport::ImageTransport>
rgb_it_;
255 #endif // RVIZ_DEPTHMAP_TO_POINTCLOUD_DISPLAY_H
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
PointCloudCommon * pointcloud_common_
std::vector< rviz::PointCloud::Point > V_Point
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
Property * topic_filter_property_
QRegularExpression filter_
Property specialized to provide getter for booleans.
boost::scoped_ptr< image_transport::ImageTransport > depthmap_it_
IntProperty * queue_size_property_
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
boost::scoped_ptr< image_transport::ImageTransport > rgb_it_
Property specialized to enforce floating point max/min.
MultiLayerDepth * ml_depth_data_
A single element of a property tree, with a name, value, description, and possibly children.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
RosFilteredTopicProperty * depth_topic_property_
BoolProperty * use_auto_size_property_
Ogre::Vector3 current_position_
EnumProperty * depth_transport_property_
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
EnumProperty * color_transport_property_
Displays a point cloud of type sensor_msgs::PointCloud.
BoolProperty * use_occlusion_compensation_property_
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::CameraInfo > > cam_info_sub_
void fillTopicList() override
std::set< std::string > transport_plugin_types_
Ogre::Quaternion current_orientation_
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
RosFilteredTopicProperty(const QString &name, const QString &default_value, const QString &message_type, const QString &description, const QRegularExpression &filter, Property *parent, Func &&changed_slot, const R *receiver)
RosFilteredTopicProperty(const QString &name=QString(), const QString &default_value=QString(), const QString &message_type=QString(), const QString &description=QString(), const QRegularExpression &filter=QRegularExpression(), Property *parent=nullptr)
void enableFilter(bool enabled)
RosFilteredTopicProperty(const QString &name, const QString &default_value, const QString &message_type, const QString &description, const QRegularExpression &filter, P *parent, Func &&changed_slot)
boost::mutex cam_info_mutex_
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
QRegularExpression filter() const
sensor_msgs::CameraInfo::ConstPtr cam_info_
uint32_t messages_received_
RosFilteredTopicProperty * color_topic_property_
FloatProperty * occlusion_shadow_timeout_property_
FloatProperty * auto_size_factor_property_
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09