Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::ROSLogicalCameraPlugin Class Reference

ROS publisher for the logical camera. More...

#include <ROSLogicalCameraPlugin.hh>

Inheritance diagram for gazebo::ROSLogicalCameraPlugin:
Inheritance graph
[legend]

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::NodeHandlerosnode
 ros node handle More...
 
sensors::SensorPtr sensor
 The logical camera sensor. More...
 

Detailed Description

ROS publisher for the logical camera.

Definition at line 37 of file ROSLogicalCameraPlugin.hh.

Constructor & Destructor Documentation

ROSLogicalCameraPlugin::ROSLogicalCameraPlugin ( )

Constructor.

Definition at line 36 of file ROSLogicalCameraPlugin.cc.

ROSLogicalCameraPlugin::~ROSLogicalCameraPlugin ( )
virtual

Destructor.

Definition at line 41 of file ROSLogicalCameraPlugin.cc.

Member Function Documentation

void ROSLogicalCameraPlugin::FindLogicalCamera ( )
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.

Parameters
[in]_parentPointer to the parent model
[in]_sdfPointer 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.

Parameters
[in]_msgThe logical camera image

Definition at line 116 of file ROSLogicalCameraPlugin.cc.

Member Data Documentation

physics::LinkPtr gazebo::ROSLogicalCameraPlugin::cameraLink
protected

Link that holds the logical camera.

Definition at line 49 of file ROSLogicalCameraPlugin.hh.

ros::Publisher gazebo::ROSLogicalCameraPlugin::imagePub
protected

ROS publisher for the logical camera image.

Definition at line 79 of file ROSLogicalCameraPlugin.hh.

transport::SubscriberPtr gazebo::ROSLogicalCameraPlugin::imageSub
protected

Subscription to logical camera image messages from gazebo.

Definition at line 70 of file ROSLogicalCameraPlugin.hh.

physics::ModelPtr gazebo::ROSLogicalCameraPlugin::model
protected

Model that contains the logical camera.

Definition at line 46 of file ROSLogicalCameraPlugin.hh.

transport::NodePtr gazebo::ROSLogicalCameraPlugin::node
protected

Node for communication with gazebo.

Definition at line 67 of file ROSLogicalCameraPlugin.hh.

std::string gazebo::ROSLogicalCameraPlugin::robotNamespace
protected

for setting ROS name space

Definition at line 73 of file ROSLogicalCameraPlugin.hh.

ros::NodeHandle* gazebo::ROSLogicalCameraPlugin::rosnode
protected

ros node handle

Definition at line 76 of file ROSLogicalCameraPlugin.hh.

sensors::SensorPtr gazebo::ROSLogicalCameraPlugin::sensor
protected

The logical camera sensor.

Definition at line 52 of file ROSLogicalCameraPlugin.hh.


The documentation for this class was generated from the following files:


osrf_gear
Author(s):
autogenerated on Wed Sep 7 2016 03:48:13