28 #ifndef MAP_CLOUD_DISPLAY_H 29 #define MAP_CLOUD_DISPLAY_H 31 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 37 #include <rtabmap_ros/MapData.h> 41 #include <sensor_msgs/PointCloud2.h> 102 virtual void reset();
103 virtual void update(
float wall_dt,
float ros_dt );
123 void causeRetransform();
127 void updateBillboardSize();
129 void updateXyzTransformer();
130 void updateColorTransformer();
133 void updateCloudParameters();
135 void downloadGraph();
139 virtual void onInitialize();
142 virtual void processMessage(
const rtabmap_ros::MapDataConstPtr& cloud );
145 void processMapData(
const rtabmap_ros::MapData& map);
150 bool transformCloud(
const CloudInfoPtr& cloud,
bool fully_update_transformers);
154 void updateTransformers(
const sensor_msgs::PointCloud2ConstPtr& cloud );
157 void loadTransformers();
159 void setPropertiesHidden(
const QList<Property*>& props,
bool hide );
GLM_FUNC_DECL genIType mask(genIType const &count)
bool new_color_transformer_
rviz::EnumProperty * style_property_
pluginlib::ClassLoader< rviz::PointCloudTransformer > * transformer_class_loader_
Displays point clouds from rtabmap::MapData.
rviz::FloatProperty * cloud_voxel_size_
rviz::FloatProperty * cloud_max_depth_
std::map< std::string, TransformerInfo > M_TransformerInfo
bool update(const T &new_val, T &my_val)
ros::AsyncSpinner spinner_
rviz::IntProperty * cloud_decimation_
rviz::EnumProperty * xyz_transformer_property_
rviz::FloatProperty * cloud_filter_ceiling_height_
rviz::FloatProperty * alpha_property_
std::map< int, CloudInfoPtr > cloud_infos_
rviz::FloatProperty * point_pixel_size_property_
M_TransformerInfo transformers_
rviz::FloatProperty * node_filtering_radius_
std::map< int, rtabmap::Transform > current_map_
rviz::BoolProperty * download_map_
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
sensor_msgs::PointCloud2ConstPtr message_
bool new_xyz_transformer_
rviz::FloatProperty * node_filtering_angle_
rviz::FloatProperty * point_world_size_property_
boost::recursive_mutex transformers_mutex_
rviz::FloatProperty * cloud_min_depth_
std::map< int, CloudInfoPtr > new_cloud_infos_
boost::shared_ptr< rviz::PointCloud > cloud_
ros::CallbackQueue cbqueue_
std::vector< std::string > V_string
rviz::FloatProperty * cloud_filter_floor_height_
Ogre::SceneManager * manager_
boost::mutex current_map_mutex_
boost::shared_ptr< CloudInfo > CloudInfoPtr
rviz::EnumProperty * color_transformer_property_
boost::mutex new_clouds_mutex_
std::vector< rviz::PointCloud::Point > transformed_points_
rviz::BoolProperty * download_graph_
Ogre::SceneNode * scene_node_