Tetrapod Project
ContactSensor Class Reference

A plugin for the contact sensors. More...

#include <contact_sensor.h>

Public Member Functions

 ContactSensor ()
 Constructor. More...
 
virtual ~ContactSensor ()
 Destructor. More...
 
void OnFlContactCallback (const ConstContactsPtr &_msg)
 The OnFlContactCallback function handles an incoming contact message from the front left contact sensor in Gazebo. More...
 
void OnFrContactCallback (const ConstContactsPtr &_msg)
 The OnFrContactCallback function handles an incoming contact message from the front right contact sensor in Gazebo. More...
 
void OnRlContactCallback (const ConstContactsPtr &_msg)
 The OnRlContactCallback function handles an incoming contact message from the rear left contact sensor in Gazebo. More...
 
void OnRrContactCallback (const ConstContactsPtr &_msg)
 The OnRrContactCallback function handles an incoming contact message from the rear rear contact sensor in Gazebo. More...
 
void PublishQueueThread ()
 The PublishQueueThread function is a ROS helper function that publish state messages. More...
 

Protected Member Functions

void InitGazebo ()
 The InitRos function is called to initialize Gazebo. More...
 
void InitRos ()
 The InitRos function is called to initialize ROS. More...
 
void InitRosQueueThreads ()
 The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads. More...
 

Private Attributes

int footContacts [4]
 Vector of foot contacts, zero indicates no contact and one indicates contact. More...
 
gazebo::transport::NodePtr gazeboNode
 Node used for Gazebo transport. More...
 
gazebo::transport::SubscriberPtr flContactSensorSub
 Gazebo front left contact sensor Subscriber. More...
 
gazebo::transport::SubscriberPtr frContactSensorSub
 Gazebo front right contact sensor Subscriber. More...
 
gazebo::transport::SubscriberPtr rlContactSensorSub
 Gazebo rear left contact sensor Subscriber. More...
 
gazebo::transport::SubscriberPtr rrContactSensorSub
 Gazebo rear right contact sensor Subscriber. More...
 
std::unique_ptr< ros::NodeHandle > rosNode
 Node used for ROS transport. More...
 
ros::Publisher contactStatePub
 ROS Contact State Publisher. More...
 
ros::CallbackQueue rosPublishQueue
 ROS callbackque that helps publish messages. More...
 
std::thread rosPublishQueueThread
 Thread running the rosPublishQueue. More...
 

Detailed Description

A plugin for the contact sensors.

Definition at line 45 of file contact_sensor.h.

Constructor & Destructor Documentation

◆ ContactSensor()

ContactSensor::ContactSensor ( )

Constructor.

Definition at line 30 of file contact_sensor.cpp.

◆ ~ContactSensor()

ContactSensor::~ContactSensor ( )
virtual

Destructor.

Definition at line 44 of file contact_sensor.cpp.

Member Function Documentation

◆ OnFlContactCallback()

void ContactSensor::OnFlContactCallback ( const ConstContactsPtr &  _msg)

The OnFlContactCallback function handles an incoming contact message from the front left contact sensor in Gazebo.

Parameters
[in]_msgA contact message.

Definition at line 56 of file contact_sensor.cpp.

◆ OnFrContactCallback()

void ContactSensor::OnFrContactCallback ( const ConstContactsPtr &  _msg)

The OnFrContactCallback function handles an incoming contact message from the front right contact sensor in Gazebo.

Parameters
[in]_msgA contact message.

Definition at line 69 of file contact_sensor.cpp.

◆ OnRlContactCallback()

void ContactSensor::OnRlContactCallback ( const ConstContactsPtr &  _msg)

The OnRlContactCallback function handles an incoming contact message from the rear left contact sensor in Gazebo.

Parameters
[in]_msgA contact message.

Definition at line 82 of file contact_sensor.cpp.

◆ OnRrContactCallback()

void ContactSensor::OnRrContactCallback ( const ConstContactsPtr &  _msg)

The OnRrContactCallback function handles an incoming contact message from the rear rear contact sensor in Gazebo.

Parameters
[in]_msgA contact message.

Definition at line 95 of file contact_sensor.cpp.

◆ PublishQueueThread()

void ContactSensor::PublishQueueThread ( )

The PublishQueueThread function is a ROS helper function that publish state messages.

Definition at line 108 of file contact_sensor.cpp.

◆ InitGazebo()

void ContactSensor::InitGazebo ( )
protected

The InitRos function is called to initialize Gazebo.

Definition at line 129 of file contact_sensor.cpp.

◆ InitRos()

void ContactSensor::InitRos ( )
protected

The InitRos function is called to initialize ROS.

Definition at line 155 of file contact_sensor.cpp.

◆ InitRosQueueThreads()

void ContactSensor::InitRosQueueThreads ( )
protected

The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.

Definition at line 185 of file contact_sensor.cpp.

Member Data Documentation

◆ footContacts

int ContactSensor::footContacts[4]
private

Vector of foot contacts, zero indicates no contact and one indicates contact.

Definition at line 89 of file contact_sensor.h.

◆ gazeboNode

gazebo::transport::NodePtr ContactSensor::gazeboNode
private

Node used for Gazebo transport.

Definition at line 92 of file contact_sensor.h.

◆ flContactSensorSub

gazebo::transport::SubscriberPtr ContactSensor::flContactSensorSub
private

Gazebo front left contact sensor Subscriber.

Definition at line 95 of file contact_sensor.h.

◆ frContactSensorSub

gazebo::transport::SubscriberPtr ContactSensor::frContactSensorSub
private

Gazebo front right contact sensor Subscriber.

Definition at line 98 of file contact_sensor.h.

◆ rlContactSensorSub

gazebo::transport::SubscriberPtr ContactSensor::rlContactSensorSub
private

Gazebo rear left contact sensor Subscriber.

Definition at line 101 of file contact_sensor.h.

◆ rrContactSensorSub

gazebo::transport::SubscriberPtr ContactSensor::rrContactSensorSub
private

Gazebo rear right contact sensor Subscriber.

Definition at line 104 of file contact_sensor.h.

◆ rosNode

std::unique_ptr<ros::NodeHandle> ContactSensor::rosNode
private

Node used for ROS transport.

Definition at line 107 of file contact_sensor.h.

◆ contactStatePub

ros::Publisher ContactSensor::contactStatePub
private

ROS Contact State Publisher.

Definition at line 110 of file contact_sensor.h.

◆ rosPublishQueue

ros::CallbackQueue ContactSensor::rosPublishQueue
private

ROS callbackque that helps publish messages.

Definition at line 113 of file contact_sensor.h.

◆ rosPublishQueueThread

std::thread ContactSensor::rosPublishQueueThread
private

Thread running the rosPublishQueue.

Definition at line 116 of file contact_sensor.h.


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