Go to the documentation of this file.
17 #ifndef GAZEBO_ROS_HARNESS_H
18 #define GAZEBO_ROS_HARNESS_H
25 #include <std_msgs/Float32.h>
26 #include <std_msgs/Bool.h>
28 #include <gazebo/plugins/HarnessPlugin.hh>
51 public:
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
55 private:
virtual void OnVelocity(
const std_msgs::Float32::ConstPtr &
msg);
60 private:
virtual void OnDetach(
const std_msgs::Bool::ConstPtr &
msg);
ros::CallbackQueue queue_
See the Gazebo documentation about the HarnessPlugin. This ROS wrapper exposes two topics:
virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg)
Receive winch velocity control messages.
ros::Subscriber detachSub_
Subscriber to detach control messages.
ros::NodeHandle * rosnode_
pointer to ros node
boost::thread callbackQueueThread_
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
std::string robotNamespace_
for setting ROS name space
virtual ~GazeboRosHarness()
Destructor.
ros::Subscriber velocitySub_
Subscriber to velocity control messages.
virtual void OnDetach(const std_msgs::Bool::ConstPtr &msg)
Receive detach messages.
GazeboRosHarness()
Constructor.
void QueueThread()
Custom callback queue thread.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55