#include <gazebo_ros_projector.h>
|
virtual void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
| Load the controller. More...
|
|
|
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...
|
|
Definition at line 75 of file gazebo_ros_projector.h.
gazebo::GazeboRosProjector::GazeboRosProjector |
( |
| ) |
|
gazebo::GazeboRosProjector::~GazeboRosProjector |
( |
| ) |
|
|
virtual |
void gazebo::GazeboRosProjector::Load |
( |
physics::ModelPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosProjector::LoadImage |
( |
const std_msgs::String::ConstPtr & |
imageMsg | ) |
|
|
private |
void gazebo::GazeboRosProjector::QueueThread |
( |
| ) |
|
|
private |
void gazebo::GazeboRosProjector::ToggleProjector |
( |
const std_msgs::Int32::ConstPtr & |
projectorMsg | ) |
|
|
private |
boost::thread gazebo::GazeboRosProjector::callback_queue_thread_ |
|
private |
transport::NodePtr gazebo::GazeboRosProjector::node_ |
|
private |
transport::PublisherPtr gazebo::GazeboRosProjector::projector_pub_ |
|
private |
std::string gazebo::GazeboRosProjector::projector_topic_name_ |
|
private |
std::string gazebo::GazeboRosProjector::robot_namespace_ |
|
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.
std::string gazebo::GazeboRosProjector::texture_topic_name_ |
|
private |
physics::WorldPtr gazebo::GazeboRosProjector::world_ |
|
private |
The documentation for this class was generated from the following files: