See the Gazebo documentation about the HarnessPlugin. This ROS wrapper exposes two topics: More...
#include <gazebo_ros_harness.h>
Public Member Functions | |
GazeboRosHarness () | |
Constructor. More... | |
virtual void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. More... | |
virtual | ~GazeboRosHarness () |
Destructor. More... | |
Private Member Functions | |
virtual void | OnDetach (const std_msgs::Bool::ConstPtr &msg) |
Receive detach messages. More... | |
virtual void | OnVelocity (const std_msgs::Float32::ConstPtr &msg) |
Receive winch velocity control messages. More... | |
void | QueueThread () |
Custom callback queue thread. More... | |
Private Attributes | |
boost::thread | callbackQueueThread_ |
ros::Subscriber | detachSub_ |
Subscriber to detach control messages. More... | |
ros::CallbackQueue | queue_ |
std::string | robotNamespace_ |
for setting ROS name space More... | |
ros::NodeHandle * | rosnode_ |
pointer to ros node More... | |
ros::Subscriber | velocitySub_ |
Subscriber to velocity control messages. More... | |
See the Gazebo documentation about the HarnessPlugin. This ROS wrapper exposes two topics:
Definition at line 42 of file gazebo_ros_harness.h.
gazebo::GazeboRosHarness::GazeboRosHarness | ( | ) |
Constructor.
Definition at line 30 of file gazebo_ros_harness.cpp.
|
virtual |
Destructor.
Definition at line 35 of file gazebo_ros_harness.cpp.
|
virtual |
Load the plugin.
Definition at line 47 of file gazebo_ros_harness.cpp.
|
privatevirtual |
Receive detach messages.
[in] | msg | Boolean detach message. Detach joints if data is true. |
Definition at line 92 of file gazebo_ros_harness.cpp.
|
privatevirtual |
Receive winch velocity control messages.
[in] | msg | Float message that is the target winch velocity. |
Definition at line 85 of file gazebo_ros_harness.cpp.
|
private |
Custom callback queue thread.
Definition at line 100 of file gazebo_ros_harness.cpp.
|
private |
Definition at line 77 of file gazebo_ros_harness.h.
|
private |
Subscriber to detach control messages.
Definition at line 72 of file gazebo_ros_harness.h.
|
private |
Definition at line 76 of file gazebo_ros_harness.h.
|
private |
for setting ROS name space
Definition at line 75 of file gazebo_ros_harness.h.
|
private |
pointer to ros node
Definition at line 66 of file gazebo_ros_harness.h.
|
private |
Subscriber to velocity control messages.
Definition at line 69 of file gazebo_ros_harness.h.