Go to the documentation of this file.
18 #ifndef _GAZEBO_ROS_PLUGINS_ELEVATOR_PLUGIN_H_
19 #define _GAZEBO_ROS_PLUGINS_ELEVATOR_PLUGIN_H_
24 #include <gazebo/plugins/ElevatorPlugin.hh>
28 #include <std_msgs/String.h>
46 public:
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
50 public:
void OnElevator(
const std_msgs::String::ConstPtr &_msg);
boost::thread callbackQueueThread_
ros::NodeHandle * rosnode_
ros node handle
ros::CallbackQueue queue_
Custom Callback Queue.
ros::Subscriber elevatorSub_
Subscribes to a topic that controls the elevator.
void OnElevator(const std_msgs::String::ConstPtr &_msg)
Receives messages on the elevator's topic.
void QueueThread()
Queu to handle callbacks.
ROS implementation of the Elevator plugin.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
virtual ~GazeboRosElevator()
Destructor.
std::string robotNamespace_
for setting ROS name space
GazeboRosElevator()
Constructor.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55