ROS publisher for the logical camera. More...
#include <ROSLogicalCameraPlugin.hh>

Public Member Functions | |
| void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
| Load the plugin. More... | |
| void | OnImage (ConstLogicalCameraImagePtr &_msg) |
| Callback for when logical camera images are received. More... | |
| ROSLogicalCameraPlugin () | |
| Constructor. More... | |
| virtual | ~ROSLogicalCameraPlugin () |
| Destructor. More... | |
Protected Member Functions | |
| void | FindLogicalCamera () |
| Searches the model links for a logical camera sensor. More... | |
Protected Attributes | |
| physics::LinkPtr | cameraLink |
| Link that holds the logical camera. More... | |
| ros::Publisher | imagePub |
| ROS publisher for the logical camera image. More... | |
| transport::SubscriberPtr | imageSub |
| Subscription to logical camera image messages from gazebo. More... | |
| physics::ModelPtr | model |
| Model that contains the logical camera. More... | |
| transport::NodePtr | node |
| Node for communication with gazebo. More... | |
| std::string | robotNamespace |
| for setting ROS name space More... | |
| ros::NodeHandle * | rosnode |
| ros node handle More... | |
| sensors::SensorPtr | sensor |
| The logical camera sensor. More... | |
ROS publisher for the logical camera.
Definition at line 37 of file ROSLogicalCameraPlugin.hh.
| ROSLogicalCameraPlugin::ROSLogicalCameraPlugin | ( | ) |
Constructor.
Definition at line 36 of file ROSLogicalCameraPlugin.cc.
|
virtual |
Destructor.
Definition at line 41 of file ROSLogicalCameraPlugin.cc.
|
protected |
Searches the model links for a logical camera sensor.
Definition at line 91 of file ROSLogicalCameraPlugin.cc.
| void ROSLogicalCameraPlugin::Load | ( | physics::ModelPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) |
Load the plugin.
| [in] | _parent | Pointer to the parent model |
| [in] | _sdf | Pointer to the SDF element of the plugin. |
Definition at line 47 of file ROSLogicalCameraPlugin.cc.
| void ROSLogicalCameraPlugin::OnImage | ( | ConstLogicalCameraImagePtr & | _msg | ) |
Callback for when logical camera images are received.
| [in] | _msg | The logical camera image |
Definition at line 116 of file ROSLogicalCameraPlugin.cc.
|
protected |
Link that holds the logical camera.
Definition at line 49 of file ROSLogicalCameraPlugin.hh.
|
protected |
ROS publisher for the logical camera image.
Definition at line 79 of file ROSLogicalCameraPlugin.hh.
|
protected |
Subscription to logical camera image messages from gazebo.
Definition at line 70 of file ROSLogicalCameraPlugin.hh.
|
protected |
Model that contains the logical camera.
Definition at line 46 of file ROSLogicalCameraPlugin.hh.
|
protected |
Node for communication with gazebo.
Definition at line 67 of file ROSLogicalCameraPlugin.hh.
|
protected |
for setting ROS name space
Definition at line 73 of file ROSLogicalCameraPlugin.hh.
|
protected |
ros node handle
Definition at line 76 of file ROSLogicalCameraPlugin.hh.
|
protected |
The logical camera sensor.
Definition at line 52 of file ROSLogicalCameraPlugin.hh.