Publishes a camera select message when a model enters a certain space. More...
#include <camera_contains_plugin.h>
Public Member Functions | |
CameraContainsPlugin () | |
void | Load (physics::WorldPtr _world, sdf::ElementPtr _sdf) override |
Private Member Functions | |
bool | contains (const std::string &name) const |
void | onUpdate (const common::UpdateInfo &info) |
Private Attributes | |
ros::CallbackQueue | callback_queue_ |
std::vector< std::string > | cameras_ |
ignition::math::OrientedBoxd | container_ |
BoxMarkerVisualizerPtr | container_visualizer_ |
bool | contains_model_ |
common::Time | last_update_time_ |
std::string | logger_prefix_ |
gazebo_video_monitor_msgs::Strings | msg_ |
ros::NodeHandlePtr | nh_ |
ros::Publisher | publisher_ |
ros::AsyncSpinner | spinner_ |
std::vector< std::string > | tracked_models_ |
event::ConnectionPtr | update_connection_ |
double | update_period_ |
physics::WorldPtr | world_ |
Publishes a camera select message when a model enters a certain space.
Tracks n models, and when one of them intersects the space of a box container, it publishes a list of camera names.
Definition at line 48 of file camera_contains_plugin.h.
gazebo::CameraContainsPlugin::CameraContainsPlugin | ( | ) |
Definition at line 27 of file camera_contains_plugin.cpp.
|
private |
Definition at line 100 of file camera_contains_plugin.cpp.
|
override |
Definition at line 31 of file camera_contains_plugin.cpp.
|
private |
Definition at line 107 of file camera_contains_plugin.cpp.
|
private |
Definition at line 66 of file camera_contains_plugin.h.
|
private |
Definition at line 62 of file camera_contains_plugin.h.
|
private |
Definition at line 63 of file camera_contains_plugin.h.
|
private |
Definition at line 73 of file camera_contains_plugin.h.
|
private |
Definition at line 71 of file camera_contains_plugin.h.
|
private |
Definition at line 76 of file camera_contains_plugin.h.
|
private |
Definition at line 57 of file camera_contains_plugin.h.
|
private |
Definition at line 70 of file camera_contains_plugin.h.
|
private |
Definition at line 65 of file camera_contains_plugin.h.
|
private |
Definition at line 69 of file camera_contains_plugin.h.
|
private |
Definition at line 67 of file camera_contains_plugin.h.
|
private |
Definition at line 61 of file camera_contains_plugin.h.
|
private |
Definition at line 77 of file camera_contains_plugin.h.
|
private |
Definition at line 75 of file camera_contains_plugin.h.
|
private |
Definition at line 59 of file camera_contains_plugin.h.