Public Member Functions | Private Member Functions | Private Attributes | List of all members
shadowrobot::SrVirtualTactileSensor Class Reference

#include <sr_virtual_tactile_sensor.hpp>

Inheritance diagram for shadowrobot::SrVirtualTactileSensor:
Inheritance graph
[legend]

Public Member Functions

virtual double get_touch_data ()
 
 SrVirtualTactileSensor (std::string name, std::string touch_name)
 
 ~SrVirtualTactileSensor ()
 
- Public Member Functions inherited from shadowrobot::SrGenericTactileSensor
void publish_current_values ()
 
 SrGenericTactileSensor (std::string name, std::string touch_name)
 
virtual ~SrGenericTactileSensor ()
 

Private Member Functions

void callback (const sr_robot_msgs::joints_dataConstPtr &msg)
 

Private Attributes

std::vector< std::string > names_joints_linked
 
ros::NodeHandle nh
 
ros::Subscriber sub
 
boost::mutex touch_mutex
 
double touch_value
 

Detailed Description

Definition at line 45 of file sr_virtual_tactile_sensor.hpp.

Constructor & Destructor Documentation

◆ SrVirtualTactileSensor()

shadowrobot::SrVirtualTactileSensor::SrVirtualTactileSensor ( std::string  name,
std::string  touch_name 
)

The Virtual Tactile sensors. For those sensor, we subscribe to the data coming from the hand and update the tactile sensor value based on this information. This should be extended to subscribe to a Gazebo touch sensor.

Parameters
namethe display name of the sensor
touch_namethe actual name of the touch sensor
Returns

Definition at line 38 of file sr_virtual_tactile_sensor.cpp.

◆ ~SrVirtualTactileSensor()

shadowrobot::SrVirtualTactileSensor::~SrVirtualTactileSensor ( )

Definition at line 67 of file sr_virtual_tactile_sensor.cpp.

Member Function Documentation

◆ callback()

void shadowrobot::SrVirtualTactileSensor::callback ( const sr_robot_msgs::joints_dataConstPtr &  msg)
private

Callback function called when a msg is received on the shadowhand__data topic. Update the touch_value based on the joint positions of the joints contained in names_joints_linked.

Parameters
msgthe message containing the joint positions

Definition at line 71 of file sr_virtual_tactile_sensor.cpp.

◆ get_touch_data()

double shadowrobot::SrVirtualTactileSensor::get_touch_data ( )
virtual

Generates a value for the sensor

Returns
the pressure value

Implements shadowrobot::SrGenericTactileSensor.

Definition at line 96 of file sr_virtual_tactile_sensor.cpp.

Member Data Documentation

◆ names_joints_linked

std::vector<std::string> shadowrobot::SrVirtualTactileSensor::names_joints_linked
private

The names from which we get the joint position.

Definition at line 79 of file sr_virtual_tactile_sensor.hpp.

◆ nh

ros::NodeHandle shadowrobot::SrVirtualTactileSensor::nh
private

Definition at line 72 of file sr_virtual_tactile_sensor.hpp.

◆ sub

ros::Subscriber shadowrobot::SrVirtualTactileSensor::sub
private

Subscribes to the shadowhand_data topic and updates the touch_value based on the joint positions

Definition at line 84 of file sr_virtual_tactile_sensor.hpp.

◆ touch_mutex

boost::mutex shadowrobot::SrVirtualTactileSensor::touch_mutex
private

Definition at line 73 of file sr_virtual_tactile_sensor.hpp.

◆ touch_value

double shadowrobot::SrVirtualTactileSensor::touch_value
private

Definition at line 74 of file sr_virtual_tactile_sensor.hpp.


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


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:14