Public Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboRosElevator Class Reference

ROS implementation of the Elevator plugin. More...

#include <gazebo_ros_elevator.h>

List of all members.

Public Member Functions

 GazeboRosElevator ()
 Constructor.
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin.
void OnElevator (const std_msgs::String::ConstPtr &_msg)
 Receives messages on the elevator's topic.
virtual ~GazeboRosElevator ()
 Destructor.

Private Member Functions

void QueueThread ()
 Queu to handle callbacks.

Private Attributes

boost::thread callbackQueueThread_
ros::Subscriber elevatorSub_
 Subscribes to a topic that controls the elevator.
ros::CallbackQueue queue_
 Custom Callback Queue.
std::string robotNamespace_
 for setting ROS name space
ros::NodeHandlerosnode_
 ros node handle

Detailed Description

ROS implementation of the Elevator plugin.

Definition at line 35 of file gazebo_ros_elevator.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 24 of file gazebo_ros_elevator.cpp.

Destructor.

Definition at line 29 of file gazebo_ros_elevator.cpp.


Member Function Documentation

void GazeboRosElevator::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the plugin.

Parameters:
[in]_modelPointer to the Model
[in]_sdfPointer to the SDF element of the plugin.

Definition at line 40 of file gazebo_ros_elevator.cpp.

void GazeboRosElevator::OnElevator ( const std_msgs::String::ConstPtr &  _msg)

Receives messages on the elevator's topic.

Parameters:
[in]_msgThe string message that contains a command.

Definition at line 80 of file gazebo_ros_elevator.cpp.

void GazeboRosElevator::QueueThread ( ) [private]

Queu to handle callbacks.

Definition at line 86 of file gazebo_ros_elevator.cpp.


Member Data Documentation

Definition at line 68 of file gazebo_ros_elevator.h.

Subscribes to a topic that controls the elevator.

Definition at line 62 of file gazebo_ros_elevator.h.

Custom Callback Queue.

Definition at line 65 of file gazebo_ros_elevator.h.

for setting ROS name space

Definition at line 56 of file gazebo_ros_elevator.h.

ros node handle

Definition at line 59 of file gazebo_ros_elevator.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Feb 23 2017 03:43:23