Note: This tutorial assumes that you have completed the previous tutorials: Using the Real Tactile Sensors or Using Simulated Tactile Sensors.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Getting Data

Description: Getting data from the tactile sensors.

Tutorial Level: BEGINNER

Accessing the data in a different node

To access the data being published by the tactile sensors, you just need to subscribe to each of the topic you're interested in. There's an example in the example folder.

Here is a very basic example to showcase this:

   1 #include <ros/ros.h>
   2 #include <std_msgs/Float64.h>
   3 
   4 void callback(const std_msgs::Float64ConstPtr& msg)
   5 {
   6     ROS_ERROR_STREAM("Touch value for the First Finger finger tip: "
   7                       << msg->data);
   8 }
   9 
  10 int main(int argc, char** argv)
  11 {
  12     ros::init(argc, argv, "test_tactile");
  13     ros::NodeHandle node_tactile;
  14 
  15     ros::Subscriber sub;
  16     sub = node_tactile.subscribe("/sr_tactile/touch/ff", 2, callback);
  17 
  18     ros::spin();
  19 
  20     return 0;
  21 }

The code explained:

  • First we initialize the node and subscribe to one of the touch sensors topic:

   1 [...]
   2     sub = node_tactile.subscribe("/sr_tactile/touch/ff", 2, callback);
   3 [...]
  • Then we print a message containing the value of the sensor in the callback function:

   1 [...]
   2 void callback(const std_msgs::Float64ConstPtr& msg)
   3 {
   4     ROS_ERROR_STREAM("Touch value for the First Finger finger tip: "
   5                       << msg->data);
   6 }
   7 [...]

Visualizing the sensor output

To visually check the sensor output, you can use rxplot. The following command displays the 5 finger tips tactile sensors in a plot:

$ rxplot /sr_tactile/touch/ff/data,\
         /sr_tactile/touch/mf/data,\
         /sr_tactile/touch/rf/data,\
         /sr_tactile/touch/lf/data,\
         /sr_tactile/touch/th/data

Wiki: sr_tactile_sensors/Tutorials/Getting Data (last edited 2011-03-29 10:16:22 by UgoCupcic)