Go to the documentation of this file. 1 #ifndef ED_PLUGIN_CONTAINER_H_
2 #define ED_PLUGIN_CONTAINER_H_
10 #include <boost/thread.hpp>
shared_ptr< const tf2_ros::Buffer > TFBufferConstPtr
std::unique_ptr< ed::LoopUsageStatus > loop_usage_status_
shared_ptr< const UpdateRequest > UpdateRequestConstPtr
const std::string & name() const
boost::mutex mutex_update_request_
void setWorld(const WorldModelConstPtr &world)
WorldModelConstPtr world_new_
void addDelta(const UpdateRequestConstPtr &delta)
void configure(InitData &init, bool reconfigure)
double loop_frequency_max_
PluginPtr loadPlugin(const std::string &plugin_name, const std::string &plugin_type, InitData &init)
TFBufferConstPtr tf_buffer_
double loop_frequency_min_
shared_ptr< const WorldModel > WorldModelConstPtr
pluginlib::ClassLoader< ed::Plugin > * class_loader_
shared_ptr< UpdateRequest > UpdateRequestPtr
double loopFrequency() const
UpdateRequestConstPtr updateRequest() const
WorldModelConstPtr world_current_
ed::shared_ptr< boost::thread > thread_
virtual ~PluginContainer()
A diagnostic task that monitors the frequency of an event.
void clearUpdateRequest()
boost::mutex mutex_world_
PluginContainer(const ed::TFBufferConstPtr &tf_buffer_)
ed::LoopUsageStatus & getLoopUsageStatus()
void setLoopFrequency(double freq)
UpdateRequestPtr update_request_
shared_ptr< Plugin > PluginPtr
std::vector< UpdateRequestConstPtr > world_deltas_