ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to read tactile sensor data from gazebo ?

asked 2019-04-17 01:44:43 -0500

microbot gravatar image

updated 2019-04-17 03:05:39 -0500

jayess gravatar image

I am working on a small project where I have to develop a custom control plugin and test it on gazebo simulation. In my Gazebo robot model I am using sr_tactile-sensors, Now I need to use that sensor output in my custom control plugin, can anyone suggest me how to do that ? I am quite new to qazebo. I am writing my control plugin in python. Would be really helpful if you can point me in the direction where I can find details about the same, I have been trying to google it myself. Thanks in advance.

edit retag flag offensive close merge delete

Comments

If you check the sr_tactile_sensors wiki page, it shows what topics that package publishes. Is that what you're asking or are you asking how to subscribe to those topics?

jayess gravatar image jayess  ( 2019-04-17 03:07:51 -0500 )edit

yea exactly, I am asking how to subscribe them

microbot gravatar image microbot  ( 2019-04-17 04:35:25 -0500 )edit

You should go through the beginner tutorials and see if this helps. If it doesn't, then please update your question with a copy and paste of your code and any errors that may arise, along with what you don't understand.

jayess gravatar image jayess  ( 2019-04-17 06:10:54 -0500 )edit

Thank you for the tutorial. Although I have seen it before, I have not understood how to write the similar listener for sr_tactile_sensors, so as far as I understand i should import sensor_msgs package and then the specific sr_tactile_sensors package aswell and then use those pre-defined commands to access the sensor data ? or should I write a specific code for it ? I have not startd writing the code for this particular part as I am still confused and did not know where to start this. Thank you in advance.

microbot gravatar image microbot  ( 2019-04-17 06:48:59 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-04-17 13:23:35 -0500

jayess gravatar image

updated 2019-04-17 13:23:54 -0500

There are a set of tutorials on the sr_tactile_sensors wiki page that may help you. For example, there's one that shows how to subscribe to the /sr_tactile/touch/ff topic. It's in C++ so I made a Python version of it (that's been combined with the subscriber tutorial:

#!/usr/bin/env python

import rospy
from std_msgs.msg import Float64


def callback(msg):
    # log the message data to the terminal
    rospy.loginfo("The value is %d", msg.data)


def listener():
    # start the node
    rospy.init_node("listener")
    # subscribe to the '/sr_tactile/touch/ff' topic
    tactile_sub = rospy.Subscriber("/sr_tactile/touch/ff", Float64, callback)
    # keep python from exiting until this node is stopped
    rospy.spin()


if __name__ == '__main__':
    listener()
edit flag offensive delete link more

Comments

Thank you very much, this is indeed helpful.

microbot gravatar image microbot  ( 2019-04-20 16:48:03 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-04-17 01:44:43 -0500

Seen: 1,193 times

Last updated: Apr 17 '19