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;
75 class MultiLayerDepth;
82 const QString& default_value = QString(),
83 const QString& message_type = QString(),
84 const QString& description = QString(),
85 const QRegExp& filter = QRegExp(),
87 const char *changed_slot = 0,
88 QObject* receiver = 0) :
97 filter_enabled_ = enabled;
101 QRegExp
filter()
const {
return filter_; }
106 QStringList filtered_strings_;
109 RosTopicProperty::fillTopicList();
112 strings_ = strings_.filter(filter_);
130 virtual void onInitialize();
133 virtual void update(
float wall_dt,
float ros_dt);
134 virtual void reset();
135 virtual void setTopic(
const QString &topic,
const QString &datatype );
138 void updateQueueSize();
143 virtual void updateTopic();
144 virtual void updateTopicFilter();
145 virtual void updateUseAutoSize();
146 virtual void updateAutoSizeFactor();
147 virtual void updateUseOcclusionCompensation();
148 virtual void updateOcclusionTimeOut();
151 void scanForTransportSubscriberPlugins();
153 typedef std::vector<rviz::PointCloud::Point>
V_Point;
155 virtual void processMessage(sensor_msgs::Image::ConstPtr msg);
156 virtual void processMessage(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImageConstPtr rgb_msg);
157 void caminfoCallback( sensor_msgs::CameraInfo::ConstPtr msg );
160 virtual void onEnable();
161 virtual void onDisable();
163 virtual void fixedFrameChanged();
175 void setStatusList( );
185 boost::scoped_ptr<image_transport::ImageTransport>
rgb_it_;
226 #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_
boost::shared_ptr< image_transport::SubscriberFilter > rgb_sub_
std::vector< rviz::PointCloud::Point > V_Point
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=0, const char *changed_slot=0, QObject *receiver=0)
virtual void fillTopicList()
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_
Property specialized to provide max/min enforcement for integers.
boost::shared_ptr< image_transport::SubscriberFilter > depthmap_sub_
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::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_
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_
uint32_t messages_received_
BoolProperty * use_auto_size_property_
boost::shared_ptr< tf::MessageFilter< sensor_msgs::Image > > depthmap_tf_filter_
RosFilteredTopicProperty * depth_topic_property_