#include <sr_generic_tactile_sensor.hpp>
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 |
Definition at line 69 of file sr_generic_tactile_sensor.hpp.
Definition at line 57 of file sr_generic_tactile_sensor.cpp.
Definition at line 101 of file sr_generic_tactile_sensor.cpp.
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
Definition at line 143 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.
req | empty request. |
res | true if the hand contains something. |
Definition at line 104 of file sr_generic_tactile_sensor.cpp.
Calls the publish_current_values for each of the tactile sensors.
Definition at line 202 of file sr_generic_tactile_sensor.cpp.
Callback for the service to check which fingers are touching, with a given force.
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. |
Definition at line 124 of file sr_generic_tactile_sensor.cpp.
Definition at line 86 of file sr_generic_tactile_sensor.hpp.
std::vector<double> shadowrobot::SrTactileSensorManager::is_hand_occupied_thresholds [protected] |
Definition at line 87 of file sr_generic_tactile_sensor.hpp.
Definition at line 83 of file sr_generic_tactile_sensor.hpp.
Definition at line 84 of file sr_generic_tactile_sensor.hpp.
std::vector<boost::shared_ptr<SrGenericTactileSensor> > shadowrobot::SrTactileSensorManager::tactile_sensors [protected] |
Definition at line 82 of file sr_generic_tactile_sensor.hpp.
ros::ServiceServer shadowrobot::SrTactileSensorManager::which_fingers_are_touching_server [protected] |
Definition at line 103 of file sr_generic_tactile_sensor.hpp.