Robotics StackExchange | Archived questions

How to subscribe to Nao tactile sensor?

Below are the codes for my listener node. What am I missing? The output doesn't show anything.

#!/usr/bin/env python
import rospy
from std_msgs.msg import String
    def callback(data):
    rospy.loginfo(rospy.get_name()+ ": I heard %s" % data.data)


def tactilelistener():
    rospy.init_node('tactilelistener', anonymous=True)
    rospy.Subscriber("tactile_touch", String, callback)
    rospy.spin()

if __name__== '__main__':
    tactilelistener()

Asked by dnth on 2014-02-20 20:28:30 UTC

Comments

Answers

I got it working with this code. Please also refer to nao_driver and nao_msgs

#!/usr/bin/env python
import rospy
from nao_msgs.msg import TactileTouch

def callback(data):
    rospy.loginfo( "I heard %u %u" % (data.button, data.state))

def tactilelistener():

    # in ROS, nodes are unique named. If two nodes with the same
    # node are launched, the previous one is kicked off. The 
    # anonymous=True flag means that rospy will choose a unique
    # name for our 'talker' node so that multiple talkers can
    # run simultaenously.
    rospy.init_node('tactilelistener', anonymous=True)

    rospy.Subscriber("tactile_touch", TactileTouch, callback)

    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

if __name__ == '__main__':
    tactilelistener()

Asked by dnth on 2014-02-23 22:49:28 UTC

Comments