Go to the documentation of this file.
49 #ifndef MAP_DISPLAY_HPP
50 #define MAP_DISPLAY_HPP
57 #include <boost/lexical_cast.hpp>
58 #include <boost/shared_ptr.hpp>
59 #include <boost/filesystem.hpp>
60 #include <boost/algorithm/string.hpp>
67 #include <QMessageBox>
68 #include <QApplication>
88 #include <std_msgs/Int32.h>
89 #include <geometry_msgs/Point32.h>
90 #include <geometry_msgs/PoseStamped.h>
91 #include <mesh_msgs/MeshGeometryStamped.h>
92 #include <mesh_msgs/MeshGeometry.h>
93 #include <mesh_msgs/GetGeometry.h>
94 #include <mesh_msgs/GetLabeledClusters.h>
101 #include <OGRE/OgreManualObject.h>
102 #include <OGRE/OgreSceneNode.h>
103 #include <OGRE/OgreSceneManager.h>
104 #include <OGRE/OgreEntity.h>
105 #include <OGRE/OgreStringConverter.h>
106 #include <OGRE/OgreMaterialManager.h>
107 #include <OGRE/OgreRay.h>
108 #include <OGRE/OgreSceneQuery.h>
109 #include <OGRE/OgreColourValue.h>
124 class StringProperty;
130 using std::shared_ptr;
132 using std::unique_ptr;
215 std::map<std::string, std::vector<float>>
m_costs;
217 std::shared_ptr<ros::NodeHandle>
m_nh;
rviz::FileProperty * m_mapFilePath
Path to map file.
void updateMap()
Update the map, based on the current data state.
std::shared_ptr< ros::NodeHandle > m_nh_p
vector< Color > m_colors
Colors.
shared_ptr< Geometry > getGeometry()
Get the geometry.
vector< Texture > m_textures
Textures.
vector< Material > m_materials
Materials.
vector< Normal > m_normals
Vertex normals.
Display class for the map plugin.
rviz_map_plugin::MeshDisplay * m_meshDisplay
Subdisplay: MeshDisplay (for showing the mesh)
rviz_map_plugin::ClusterLabelDisplay * m_clusterLabelDisplay
Subdisplay: ClusterLabel (for showing the clusters)
shared_ptr< Geometry > m_geometry
Geometry.
std::map< std::string, std::vector< float > > m_costs
rviz::Display * createDisplay(const QString &class_id)
Create a RViz display from it's unique class_id.
vector< TexCoords > m_texCoords
Texture coordinates.
void onEnable()
RViz callback on enable.
virtual void load(const rviz::Config &config)
void onDisable()
RViz callback on disable.
Display for showing the mesh in different modes.
void saveLabel(Cluster cluster)
Saves a label to HDF5.
vector< Cluster > m_clusterList
Clusters.
void onInitialize()
RViz callback on initialize.
Master display for the Mesh- and Cluster- subdisplays. THis implementation uses HDF5 as it's data sou...
std::shared_ptr< ros::NodeHandle > m_nh
bool loadData()
Read all data from the HDF5 file and save it in the member variables.
std::string m_map_file_loaded
rviz_map_plugin
Author(s): Sebastian Pütz
, Kristin Schmidt , Jan Philipp Vogtherr , Malte kleine Piening
autogenerated on Sun Jan 21 2024 04:06:25