#include <gazebo_ros_projector.h>
Public Member Functions | |
GazeboRosProjector () | |
Constructor. | |
virtual | ~GazeboRosProjector () |
Destructor. | |
Protected Member Functions | |
virtual void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load the controller. | |
Private Member Functions | |
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 | |
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. | |
ros::Subscriber | projectorSubscriber_ |
ros::CallbackQueue | queue_ |
std::string | robot_namespace_ |
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 | texture_topic_name_ |
ROS texture topic name. | |
physics::WorldPtr | world_ |
pointer to the world |
Definition at line 75 of file gazebo_ros_projector.h.
Constructor.
parent | The parent entity, must be a Model |
Definition at line 54 of file gazebo_ros_projector.cpp.
gazebo::GazeboRosProjector::~GazeboRosProjector | ( | ) | [virtual] |
Destructor.
Definition at line 62 of file gazebo_ros_projector.cpp.
void gazebo::GazeboRosProjector::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [protected, virtual] |
Load the controller.
node | XML config node |
Definition at line 75 of file gazebo_ros_projector.cpp.
void gazebo::GazeboRosProjector::LoadImage | ( | const std_msgs::String::ConstPtr & | imageMsg | ) | [private] |
Callback when a texture is published.
Definition at line 141 of file gazebo_ros_projector.cpp.
void gazebo::GazeboRosProjector::QueueThread | ( | ) | [private] |
Definition at line 162 of file gazebo_ros_projector.cpp.
void gazebo::GazeboRosProjector::ToggleProjector | ( | const std_msgs::Int32::ConstPtr & | projectorMsg | ) | [private] |
Callbakc when a projector toggle is published.
Definition at line 151 of file gazebo_ros_projector.cpp.
Definition at line 116 of file gazebo_ros_projector.h.
boost::thread gazebo::GazeboRosProjector::callback_queue_thread_ [private] |
Definition at line 114 of file gazebo_ros_projector.h.
Definition at line 99 of file gazebo_ros_projector.h.
transport::NodePtr gazebo::GazeboRosProjector::node_ [private] |
Definition at line 118 of file gazebo_ros_projector.h.
transport::PublisherPtr gazebo::GazeboRosProjector::projector_pub_ [private] |
Definition at line 119 of file gazebo_ros_projector.h.
std::string gazebo::GazeboRosProjector::projector_topic_name_ [private] |
ROS projector topic name.
Definition at line 106 of file gazebo_ros_projector.h.
Definition at line 100 of file gazebo_ros_projector.h.
Definition at line 112 of file gazebo_ros_projector.h.
std::string gazebo::GazeboRosProjector::robot_namespace_ [private] |
For setting ROS name space.
Definition at line 109 of file gazebo_ros_projector.h.
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] |
ROS texture topic name.
Definition at line 103 of file gazebo_ros_projector.h.
physics::WorldPtr gazebo::GazeboRosProjector::world_ [private] |
pointer to the world
Definition at line 89 of file gazebo_ros_projector.h.