gazebo::GazeboRosProjector Class Reference
[Plugin XML Reference and Example]

#include <gazebo_ros_projector.h>

List of all members.

Classes

class  Projector

Public Member Functions

 GazeboRosProjector (Entity *parent)
 Constructor.
virtual ~GazeboRosProjector ()
 Destructor.

Protected Member Functions

virtual void FiniChild ()
 Finalize the controller, unadvertise topics.
virtual void InitChild ()
 Init the controller.
virtual void LoadChild (XMLConfigNode *node)
 Load the controller.
virtual void UpdateChild ()
 Update the controller.

Private Member Functions

Ogre::Root * getRootP ()
 Utility method for accessing the root Ogre object.
void LoadImage (const std_msgs::String::ConstPtr &imageMsg)
 Callback when a texture is published.
void QueueThread ()
void ToggleProjector (const std_msgs::Int32::ConstPtr &projectorMsg)
 Callbakc when a projector toggle is published.

Private Attributes

std::string bodyName
ParamT< std::string > * bodyNameP
boost::thread callback_queue_thread_
double farClipDist
ParamT< double > * farClipDistP
std::string filterNodeName
std::string filterTextureName
ParamT< std::string > * filterTextureNameP
double fov
ParamT< double > * fovP
ros::Subscriber imageSubscriber_
boost::mutex lock
 A mutex to lock access to fields that are used in ROS message callbacks.
Body * myBody
 A pointer to the body entity.
Model * myParent
 A pointer to the parent entity.
double nearClipDist
ParamT< double > * nearClipDistP
Projector projector_
ros::Subscriber projectorSubscriber_
std::string projectorTopicName
 ROS projector topic name.
ParamT< std::string > * projectorTopicNameP
ros::CallbackQueue queue_
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 For setting ROS name space.
ros::NodeHandle * rosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string textureName
ParamT< std::string > * textureNameP
std::string textureTopicName
 ROS texture topic name.
ParamT< std::string > * textureTopicNameP
 ROS Projector topic names.

Detailed Description

Definition at line 74 of file gazebo_ros_projector.h.


Constructor & Destructor Documentation

GazeboRosProjector::GazeboRosProjector ( Entity *  parent  ) 

Constructor.

Parameters:
parent The parent entity, must be a Model or a Sensor

Definition at line 47 of file gazebo_ros_projector.cpp.

GazeboRosProjector::~GazeboRosProjector (  )  [virtual]

Destructor.

Definition at line 79 of file gazebo_ros_projector.cpp.


Member Function Documentation

void GazeboRosProjector::FiniChild (  )  [protected, virtual]

Finalize the controller, unadvertise topics.

Definition at line 203 of file gazebo_ros_projector.cpp.

Ogre::Root * GazeboRosProjector::getRootP (  )  [private]

Utility method for accessing the root Ogre object.

Definition at line 215 of file gazebo_ros_projector.cpp.

void GazeboRosProjector::InitChild (  )  [protected, virtual]

Init the controller.

Definition at line 153 of file gazebo_ros_projector.cpp.

void GazeboRosProjector::LoadChild ( XMLConfigNode *  node  )  [protected, virtual]

Load the controller.

Parameters:
node XML config node

Definition at line 97 of file gazebo_ros_projector.cpp.

void GazeboRosProjector::LoadImage ( const std_msgs::String::ConstPtr &  imageMsg  )  [private]

Callback when a texture is published.

Definition at line 172 of file gazebo_ros_projector.cpp.

void GazeboRosProjector::QueueThread (  )  [private]

Definition at line 222 of file gazebo_ros_projector.cpp.

void GazeboRosProjector::ToggleProjector ( const std_msgs::Int32::ConstPtr &  projectorMsg  )  [private]

Callbakc when a projector toggle is published.

Definition at line 184 of file gazebo_ros_projector.cpp.

void GazeboRosProjector::UpdateChild (  )  [protected, virtual]

Update the controller.

Definition at line 196 of file gazebo_ros_projector.cpp.


Member Data Documentation

std::string gazebo::GazeboRosProjector::bodyName [private]

Definition at line 138 of file gazebo_ros_projector.h.

ParamT<std::string>* gazebo::GazeboRosProjector::bodyNameP [private]

Definition at line 124 of file gazebo_ros_projector.h.

Definition at line 152 of file gazebo_ros_projector.h.

Definition at line 143 of file gazebo_ros_projector.h.

ParamT<double>* gazebo::GazeboRosProjector::farClipDistP [private]

Definition at line 129 of file gazebo_ros_projector.h.

Definition at line 154 of file gazebo_ros_projector.h.

Definition at line 140 of file gazebo_ros_projector.h.

ParamT<std::string>* gazebo::GazeboRosProjector::filterTextureNameP [private]

Definition at line 126 of file gazebo_ros_projector.h.

Definition at line 141 of file gazebo_ros_projector.h.

ParamT<double>* gazebo::GazeboRosProjector::fovP [private]

Definition at line 127 of file gazebo_ros_projector.h.

Definition at line 114 of file gazebo_ros_projector.h.

boost::mutex gazebo::GazeboRosProjector::lock [private]

A mutex to lock access to fields that are used in ROS message callbacks.

Definition at line 118 of file gazebo_ros_projector.h.

A pointer to the body entity.

Definition at line 110 of file gazebo_ros_projector.h.

A pointer to the parent entity.

Definition at line 106 of file gazebo_ros_projector.h.

Definition at line 142 of file gazebo_ros_projector.h.

ParamT<double>* gazebo::GazeboRosProjector::nearClipDistP [private]

Definition at line 128 of file gazebo_ros_projector.h.

Definition at line 210 of file gazebo_ros_projector.h.

Definition at line 115 of file gazebo_ros_projector.h.

ROS projector topic name.

Definition at line 135 of file gazebo_ros_projector.h.

ParamT<std::string>* gazebo::GazeboRosProjector::projectorTopicNameP [private]

Definition at line 123 of file gazebo_ros_projector.h.

ros::CallbackQueue gazebo::GazeboRosProjector::queue_ [private]

Definition at line 150 of file gazebo_ros_projector.h.

Definition at line 147 of file gazebo_ros_projector.h.

ParamT<std::string>* gazebo::GazeboRosProjector::robotNamespaceP [private]

For setting ROS name space.

Definition at line 146 of file gazebo_ros_projector.h.

ros::NodeHandle* gazebo::GazeboRosProjector::rosnode_ [private]

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 113 of file gazebo_ros_projector.h.

Definition at line 139 of file gazebo_ros_projector.h.

ParamT<std::string>* gazebo::GazeboRosProjector::textureNameP [private]

Definition at line 125 of file gazebo_ros_projector.h.

ROS texture topic name.

Definition at line 132 of file gazebo_ros_projector.h.

ParamT<std::string>* gazebo::GazeboRosProjector::textureTopicNameP [private]

ROS Projector topic names.

inputs

Definition at line 122 of file gazebo_ros_projector.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Friends Defines


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Fri Jan 11 10:09:35 2013