Go to the documentation of this file.
18 #ifndef GAZEBO_VIDEO_MONITOR_PLUGINS_CAMERA_CONTAINS_PLUGIN_H
19 #define GAZEBO_VIDEO_MONITOR_PLUGINS_CAMERA_CONTAINS_PLUGIN_H
26 #include <gazebo/common/Plugin.hh>
27 #include <gazebo/physics/physics.hh>
29 #include <gazebo_video_monitor_msgs/Strings.h>
51 void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
override;
54 bool contains(
const std::string &name)
const;
55 void onUpdate(
const common::UpdateInfo &info);
70 gazebo_video_monitor_msgs::Strings
msg_;
82 #endif // GAZEBO_VIDEO_MONITOR_PLUGINS_CAMERA_CONTAINS_PLUGIN_H
ros::AsyncSpinner spinner_
BoxMarkerVisualizerPtr container_visualizer_
ros::Publisher publisher_
std::shared_ptr< BoxMarkerVisualizer > BoxMarkerVisualizerPtr
std::vector< std::string > tracked_models_
std::vector< std::string > cameras_
gazebo_video_monitor_msgs::Strings msg_
void onUpdate(const common::UpdateInfo &info)
ignition::math::OrientedBoxd container_
ros::CallbackQueue callback_queue_
bool contains(const std::string &name) const
Publishes a camera select message when a model enters a certain space.
common::Time last_update_time_
void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf) override
event::ConnectionPtr update_connection_
std::string logger_prefix_