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> 64 class SubscriberFilter;
74 class MultiLayerDepth;
81 const QString& default_value = QString(),
82 const QString& message_type = QString(),
83 const QString& description = QString(),
84 const QRegExp& filter = QRegExp(),
86 const char* changed_slot =
nullptr,
87 QObject* receiver =
nullptr)
90 , filter_enabled_(true)
97 filter_enabled_ = enabled;
109 QStringList filtered_strings_;
112 RosTopicProperty::fillTopicList();
115 strings_ = strings_.filter(filter_);
134 void onInitialize()
override;
137 void update(
float wall_dt,
float ros_dt)
override;
138 void reset()
override;
139 void setTopic(
const QString& topic,
const QString&
datatype)
override;
142 void updateQueueSize();
147 virtual void updateTopic();
148 virtual void updateTopicFilter();
149 virtual void updateUseAutoSize();
150 virtual void updateAutoSizeFactor();
151 virtual void updateUseOcclusionCompensation();
152 virtual void updateOcclusionTimeOut();
155 void scanForTransportSubscriberPlugins();
157 typedef std::vector<rviz::PointCloud::Point>
V_Point;
159 virtual void processMessage(sensor_msgs::Image::ConstPtr msg);
160 virtual void processMessage(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr rgb_msg);
161 void caminfoCallback(sensor_msgs::CameraInfo::ConstPtr msg);
164 void onEnable()
override;
165 void onDisable()
override;
167 void fixedFrameChanged()
override;
179 void setStatusList();
189 boost::scoped_ptr<image_transport::ImageTransport>
rgb_it_;
229 #endif // RVIZ_DEPTHMAP_TO_POINTCLOUD_DISPLAY_H
Ogre::Quaternion current_orientation_
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
boost::scoped_ptr< image_transport::ImageTransport > rgb_it_
RosFilteredTopicProperty(const QString &name=QString(), const QString &default_value=QString(), const QString &message_type=QString(), const QString &description=QString(), const QRegExp &filter=QRegExp(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
std::vector< rviz::PointCloud::Point > V_Point
FloatProperty * auto_size_factor_property_
A single element of a property tree, with a name, value, description, and possibly children...
MultiLayerDepth * ml_depth_data_
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
Property specialized to enforce floating point max/min.
void enableFilter(bool enabled)
sensor_msgs::CameraInfo::ConstPtr cam_info_
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
Property specialized to provide max/min enforcement for integers.
Displays a point cloud of type sensor_msgs::PointCloud.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::set< std::string > transport_plugin_types_
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
boost::scoped_ptr< image_transport::ImageTransport > depthmap_it_
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::CameraInfo > > cam_info_sub_
void fillTopicList() override
boost::mutex cam_info_mutex_
RosFilteredTopicProperty * color_topic_property_
BoolProperty * use_occlusion_compensation_property_
PointCloudCommon * pointcloud_common_
IntProperty * queue_size_property_
Ogre::Vector3 current_position_
Property specialized to provide getter for booleans.
EnumProperty * depth_transport_property_
FloatProperty * occlusion_shadow_timeout_property_
EnumProperty * color_transport_property_
Property * topic_filter_property_
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
uint32_t messages_received_
BoolProperty * use_auto_size_property_
RosFilteredTopicProperty * depth_topic_property_