ROS implementation of the Elevator plugin. More...
#include <gazebo_ros_elevator.h>
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::NodeHandle * | rosnode_ |
ros node handle |
ROS implementation of the Elevator plugin.
Definition at line 35 of file gazebo_ros_elevator.h.
Constructor.
Definition at line 24 of file gazebo_ros_elevator.cpp.
GazeboRosElevator::~GazeboRosElevator | ( | ) | [virtual] |
Destructor.
Definition at line 29 of file gazebo_ros_elevator.cpp.
void GazeboRosElevator::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the plugin.
[in] | _model | Pointer to the Model |
[in] | _sdf | Pointer 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.
[in] | _msg | The 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.
boost::thread gazebo::GazeboRosElevator::callbackQueueThread_ [private] |
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.