#include <sr_generic_tactile_sensor.hpp>
|
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) |
|
shadowrobot::SrTactileSensorManager::SrTactileSensorManager |
( |
| ) |
|
shadowrobot::SrTactileSensorManager::~SrTactileSensorManager |
( |
| ) |
|
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.
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
-
req | empty request. |
res | true if the hand contains something. |
- Returns
Definition at line 115 of file sr_generic_tactile_sensor.cpp.
void shadowrobot::SrTactileSensorManager::publish_all |
( |
| ) |
|
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
-
req | contains the forces thresholds for each finger. |
res | a 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.
std::vector<double> shadowrobot::SrTactileSensorManager::is_hand_occupied_thresholds |
|
protected |
ros::Rate shadowrobot::SrTactileSensorManager::publish_rate |
|
protected |
The documentation for this class was generated from the following files: