#include <sr_virtual_tactile_sensor.hpp>
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::string > | names_joints_linked |
ros::NodeHandle | nh |
ros::Subscriber | sub |
boost::mutex | touch_mutex |
double | touch_value |
Definition at line 43 of file sr_virtual_tactile_sensor.hpp.
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.
name | the display name of the sensor |
touch_name | the actual name of the touch sensor |
Definition at line 37 of file sr_virtual_tactile_sensor.cpp.
Definition at line 66 of file sr_virtual_tactile_sensor.cpp.
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.
msg | the message containing the joint positions |
Definition at line 69 of file sr_virtual_tactile_sensor.cpp.
double shadowrobot::SrVirtualTactileSensor::get_touch_data | ( | ) | [virtual] |
Generates a value for the sensor
Implements shadowrobot::SrGenericTactileSensor.
Definition at line 94 of file sr_virtual_tactile_sensor.cpp.
std::vector<std::string> shadowrobot::SrVirtualTactileSensor::names_joints_linked [private] |
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.
boost::mutex shadowrobot::SrVirtualTactileSensor::touch_mutex [private] |
Definition at line 69 of file sr_virtual_tactile_sensor.hpp.
double shadowrobot::SrVirtualTactileSensor::touch_value [private] |
Definition at line 70 of file sr_virtual_tactile_sensor.hpp.