Public Member Functions | Private Member Functions | Private Attributes
shadowrobot::SrVirtualTactileSensor Class Reference

#include <sr_virtual_tactile_sensor.hpp>

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

List of all members.

Public Member Functions

virtual double get_touch_data ()
 SrVirtualTactileSensor (std::string name, std::string touch_name)
 ~SrVirtualTactileSensor ()

Private Member Functions

void callback (const sr_robot_msgs::joints_dataConstPtr &msg)

Private Attributes

std::vector< std::stringnames_joints_linked
ros::NodeHandle nh
ros::Subscriber sub
boost::mutex touch_mutex
double touch_value

Detailed Description

Definition at line 43 of file sr_virtual_tactile_sensor.hpp.


Constructor & Destructor Documentation

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 37 of file sr_virtual_tactile_sensor.cpp.

Definition at line 66 of file sr_virtual_tactile_sensor.cpp.


Member Function Documentation

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 69 of file sr_virtual_tactile_sensor.cpp.

Generates a value for the sensor

Returns:
the pressure value

Implements shadowrobot::SrGenericTactileSensor.

Definition at line 94 of file sr_virtual_tactile_sensor.cpp.


Member Data Documentation

The names from which we get the joint position.

Definition at line 75 of file sr_virtual_tactile_sensor.hpp.

Definition at line 68 of file sr_virtual_tactile_sensor.hpp.

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

Definition at line 80 of file sr_virtual_tactile_sensor.hpp.

Definition at line 69 of file sr_virtual_tactile_sensor.hpp.

Definition at line 70 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 Fri Aug 21 2015 12:27:01