Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
shadowrobot::SrTactileSensorManager Class Reference

#include <sr_generic_tactile_sensor.hpp>

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

Public Member Functions

void publish_all ()
 
 SrTactileSensorManager ()
 
 ~SrTactileSensorManager ()
 

Protected Member Functions

std::vector< std::vector< std::string > > get_all_names ()
 
bool is_hand_occupied_cb (sr_robot_msgs::is_hand_occupied::Request &req, sr_robot_msgs::is_hand_occupied::Response &res)
 
bool which_fingers_are_touching_cb (sr_robot_msgs::which_fingers_are_touching::Request &req, sr_robot_msgs::which_fingers_are_touching::Response &res)
 

Protected Attributes

ros::ServiceServer is_hand_occupied_server
 
std::vector< double > is_hand_occupied_thresholds
 
ros::NodeHandle n_tilde
 
ros::Rate publish_rate
 
std::vector< boost::shared_ptr< SrGenericTactileSensor > > tactile_sensors
 
ros::ServiceServer which_fingers_are_touching_server
 

Detailed Description

Definition at line 73 of file sr_generic_tactile_sensor.hpp.

Constructor & Destructor Documentation

◆ SrTactileSensorManager()

shadowrobot::SrTactileSensorManager::SrTactileSensorManager ( )

Definition at line 61 of file sr_generic_tactile_sensor.cpp.

◆ ~SrTactileSensorManager()

shadowrobot::SrTactileSensorManager::~SrTactileSensorManager ( )

Definition at line 111 of file sr_generic_tactile_sensor.cpp.

Member Function Documentation

◆ get_all_names()

std::vector< std::vector< std::string > > shadowrobot::SrTactileSensorManager::get_all_names ( )
protected

Get all the necessary names for the tactile sensors: the display names, the touch sensor name (for the robot).

Those names are read from the parameter server. They are stored in params/sensor_names.yaml

Returns
a vector containing 3 vectors for the display_names and the sensor_touch_names ; in this order.

Definition at line 159 of file sr_generic_tactile_sensor.cpp.

◆ is_hand_occupied_cb()

bool shadowrobot::SrTactileSensorManager::is_hand_occupied_cb ( sr_robot_msgs::is_hand_occupied::Request &  req,
sr_robot_msgs::is_hand_occupied::Response &  res 
)
protected

Callback for the service to check if the hand is occupied. This is were we actually check if the hand is holding something or not.

For the time being, we simply check if the sensors have a bigger value than a list of thresholds.

Parameters
reqempty request.
restrue if the hand contains something.
Returns

Definition at line 115 of file sr_generic_tactile_sensor.cpp.

◆ publish_all()

void shadowrobot::SrTactileSensorManager::publish_all ( )

Calls the publish_current_values for each of the tactile sensors.

Definition at line 228 of file sr_generic_tactile_sensor.cpp.

◆ which_fingers_are_touching_cb()

bool shadowrobot::SrTactileSensorManager::which_fingers_are_touching_cb ( sr_robot_msgs::which_fingers_are_touching::Request &  req,
sr_robot_msgs::which_fingers_are_touching::Response &  res 
)
protected

Callback for the service to check which fingers are touching, with a given force.

Parameters
reqcontains the forces thresholds for each finger.
resa vector of 5 doubles representing the contact forces. If 0.0 -> not touching, if > 0.0 -> current force.
Returns

Definition at line 136 of file sr_generic_tactile_sensor.cpp.

Member Data Documentation

◆ is_hand_occupied_server

ros::ServiceServer shadowrobot::SrTactileSensorManager::is_hand_occupied_server
protected

Definition at line 91 of file sr_generic_tactile_sensor.hpp.

◆ is_hand_occupied_thresholds

std::vector<double> shadowrobot::SrTactileSensorManager::is_hand_occupied_thresholds
protected

Definition at line 92 of file sr_generic_tactile_sensor.hpp.

◆ n_tilde

ros::NodeHandle shadowrobot::SrTactileSensorManager::n_tilde
protected

Definition at line 88 of file sr_generic_tactile_sensor.hpp.

◆ publish_rate

ros::Rate shadowrobot::SrTactileSensorManager::publish_rate
protected

Definition at line 89 of file sr_generic_tactile_sensor.hpp.

◆ tactile_sensors

std::vector<boost::shared_ptr<SrGenericTactileSensor> > shadowrobot::SrTactileSensorManager::tactile_sensors
protected

Definition at line 87 of file sr_generic_tactile_sensor.hpp.

◆ which_fingers_are_touching_server

ros::ServiceServer shadowrobot::SrTactileSensorManager::which_fingers_are_touching_server
protected

Definition at line 109 of file sr_generic_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