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

#include <gazebo_ros_projector.h>

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

Public Member Functions

 GazeboRosProjector ()
 Constructor. More...
 
virtual ~GazeboRosProjector ()
 Destructor. More...
 

Protected Member Functions

virtual void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load the controller. More...
 

Private Member Functions

void LoadImage (const std_msgs::String::ConstPtr &imageMsg)
 Callback when a texture is published. More...
 
void QueueThread ()
 
void ToggleProjector (const std_msgs::Int32::ConstPtr &projectorMsg)
 Callbakc when a projector toggle is published. More...
 

Private Attributes

event::ConnectionPtr add_model_event_
 
boost::thread callback_queue_thread_
 
ros::Subscriber imageSubscriber_
 
transport::NodePtr node_
 
transport::PublisherPtr projector_pub_
 
std::string projector_topic_name_
 ROS projector topic name. More...
 
ros::Subscriber projectorSubscriber_
 
ros::CallbackQueue queue_
 
std::string robot_namespace_
 For setting ROS name space. More...
 
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist. More...
 
std::string texture_topic_name_
 ROS texture topic name. More...
 
physics::WorldPtr world_
 pointer to the world More...
 

Detailed Description

Definition at line 75 of file gazebo_ros_projector.h.

Constructor & Destructor Documentation

◆ GazeboRosProjector()

gazebo::GazeboRosProjector::GazeboRosProjector ( )

Constructor.

Parameters
parentThe parent entity, must be a Model

Definition at line 58 of file gazebo_ros_projector.cpp.

◆ ~GazeboRosProjector()

gazebo::GazeboRosProjector::~GazeboRosProjector ( )
virtual

Destructor.

Definition at line 66 of file gazebo_ros_projector.cpp.

Member Function Documentation

◆ Load()

void gazebo::GazeboRosProjector::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)
protectedvirtual

Load the controller.

Parameters
nodeXML config node

Definition at line 79 of file gazebo_ros_projector.cpp.

◆ LoadImage()

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

Callback when a texture is published.

Definition at line 146 of file gazebo_ros_projector.cpp.

◆ QueueThread()

void gazebo::GazeboRosProjector::QueueThread ( )
private

Definition at line 181 of file gazebo_ros_projector.cpp.

◆ ToggleProjector()

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

Callbakc when a projector toggle is published.

Definition at line 163 of file gazebo_ros_projector.cpp.

Member Data Documentation

◆ add_model_event_

event::ConnectionPtr gazebo::GazeboRosProjector::add_model_event_
private

Definition at line 116 of file gazebo_ros_projector.h.

◆ callback_queue_thread_

boost::thread gazebo::GazeboRosProjector::callback_queue_thread_
private

Definition at line 114 of file gazebo_ros_projector.h.

◆ imageSubscriber_

ros::Subscriber gazebo::GazeboRosProjector::imageSubscriber_
private

Definition at line 99 of file gazebo_ros_projector.h.

◆ node_

transport::NodePtr gazebo::GazeboRosProjector::node_
private

Definition at line 118 of file gazebo_ros_projector.h.

◆ projector_pub_

transport::PublisherPtr gazebo::GazeboRosProjector::projector_pub_
private

Definition at line 119 of file gazebo_ros_projector.h.

◆ projector_topic_name_

std::string gazebo::GazeboRosProjector::projector_topic_name_
private

ROS projector topic name.

Definition at line 106 of file gazebo_ros_projector.h.

◆ projectorSubscriber_

ros::Subscriber gazebo::GazeboRosProjector::projectorSubscriber_
private

Definition at line 100 of file gazebo_ros_projector.h.

◆ queue_

ros::CallbackQueue gazebo::GazeboRosProjector::queue_
private

Definition at line 112 of file gazebo_ros_projector.h.

◆ robot_namespace_

std::string gazebo::GazeboRosProjector::robot_namespace_
private

For setting ROS name space.

Definition at line 109 of file gazebo_ros_projector.h.

◆ rosnode_

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 98 of file gazebo_ros_projector.h.

◆ texture_topic_name_

std::string gazebo::GazeboRosProjector::texture_topic_name_
private

ROS texture topic name.

Definition at line 103 of file gazebo_ros_projector.h.

◆ world_

physics::WorldPtr gazebo::GazeboRosProjector::world_
private

pointer to the world

Definition at line 89 of file gazebo_ros_projector.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28