Go to the documentation of this file.
10 #include <diagnostic_updater/diagnostic_updater.h>
12 #include <ros/publisher.h>
14 #include <tf2_ros/buffer.h>
25 class TransformListener;
43 void reset(
bool keep_all_shapes =
false);
std::map< std::string, SensorModulePtr > sensors_
Sensor data.
shared_ptr< const tf2_ros::Buffer > TFBufferConstPtr
shared_ptr< tf2_ros::Buffer > TFBufferPtr
void reset(bool keep_all_shapes=false)
PropertyKeyDB property_key_db_
Property Key DB.
void storeEntityMeasurements(const std::string &path) const
const PropertyKeyDBEntry * getPropertyKeyDBEntry(const std::string &name) const
void configure(tue::Configuration &config, bool reconfigure=false)
diagnostic_updater::Updater updater_
Profiling.
shared_ptr< PluginContainer > PluginContainerPtr
std::queue< UpdateRequest > update_requests_
WorldModelConstPtr world_model_
PluginContainerPtr loadPlugin(const std::string &plugin_name, tue::Configuration config)
shared_ptr< const WorldModel > WorldModelConstPtr
WorldModelConstPtr world_model() const
std::map< std::string, PluginContainerPtr > plugin_containers_
Plugins.
models::ModelLoader model_loader_
Model loading.
TFBufferConstPtr tf_buffer_const_
std::string world_name_
World name.
ros::Publisher pub_stats_
const PropertyKeyDBEntry * getPropertyKeyDBEntry(const std::string &name) const
ed::shared_ptr< tf2_ros::TransformListener > tf_listener_
boost::mutex mutex_world_
std::map< std::string, PluginContainerPtr > inactive_plugin_containers_
tue::config::ReaderWriter config