Public Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosHarness Class Reference

See the Gazebo documentation about the HarnessPlugin. This ROS wrapper exposes two topics: More...

#include <gazebo_ros_harness.h>

Inheritance diagram for gazebo::GazeboRosHarness:
Inheritance graph
[legend]

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::NodeHandlerosnode_
 pointer to ros node More...
 
ros::Subscriber velocitySub_
 Subscriber to velocity control messages. More...
 

Detailed Description

See the Gazebo documentation about the HarnessPlugin. This ROS wrapper exposes two topics:

  1. /<plugin_model_name>/harness/velocity
    • Message Type: std_msgs::Float32
    • Purpose: Set target winch velocity
  2. /<plugin_model_name>/harness/detach
    • Message Type: std_msgs::Bool
    • Purpose: Detach the <detach> joint.

Definition at line 42 of file gazebo_ros_harness.h.

Constructor & Destructor Documentation

gazebo::GazeboRosHarness::GazeboRosHarness ( )

Constructor.

Definition at line 30 of file gazebo_ros_harness.cpp.

gazebo::GazeboRosHarness::~GazeboRosHarness ( )
virtual

Destructor.

Definition at line 35 of file gazebo_ros_harness.cpp.

Member Function Documentation

void gazebo::GazeboRosHarness::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Load the plugin.

Definition at line 47 of file gazebo_ros_harness.cpp.

void gazebo::GazeboRosHarness::OnDetach ( const std_msgs::Bool::ConstPtr &  msg)
privatevirtual

Receive detach messages.

Parameters
[in]msgBoolean detach message. Detach joints if data is true.

Definition at line 92 of file gazebo_ros_harness.cpp.

void gazebo::GazeboRosHarness::OnVelocity ( const std_msgs::Float32::ConstPtr &  msg)
privatevirtual

Receive winch velocity control messages.

Parameters
[in]msgFloat message that is the target winch velocity.

Definition at line 85 of file gazebo_ros_harness.cpp.

void gazebo::GazeboRosHarness::QueueThread ( )
private

Custom callback queue thread.

Definition at line 100 of file gazebo_ros_harness.cpp.

Member Data Documentation

boost::thread gazebo::GazeboRosHarness::callbackQueueThread_
private

Definition at line 77 of file gazebo_ros_harness.h.

ros::Subscriber gazebo::GazeboRosHarness::detachSub_
private

Subscriber to detach control messages.

Definition at line 72 of file gazebo_ros_harness.h.

ros::CallbackQueue gazebo::GazeboRosHarness::queue_
private

Definition at line 76 of file gazebo_ros_harness.h.

std::string gazebo::GazeboRosHarness::robotNamespace_
private

for setting ROS name space

Definition at line 75 of file gazebo_ros_harness.h.

ros::NodeHandle* gazebo::GazeboRosHarness::rosnode_
private

pointer to ros node

Definition at line 66 of file gazebo_ros_harness.h.

ros::Subscriber gazebo::GazeboRosHarness::velocitySub_
private

Subscriber to velocity control messages.

Definition at line 69 of file gazebo_ros_harness.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Apr 6 2021 02:19:40