joy_to_twist.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib; roslib.load_manifest('thymio_navigation_driver')
00003 import rospy
00004 from geometry_msgs.msg import Twist
00005 from sensor_msgs.msg import Joy
00006 
00007 class JoyToTwist(object):
00008         def __init__(self):
00009                 rospy.Subscriber('/joy', Joy, self.joy_cb)
00010                 self.cmdvel_pub = rospy.Publisher('/cmd_vel', Twist)
00011         
00012         def joy_cb(self, joy):
00013                 tw = Twist()
00014                 tw.linear.x = 0.15*joy.axes[1]
00015                 tw.angular.z = 2.*joy.axes[0]
00016                 self.cmdvel_pub.publish(tw)
00017 
00018 ## Create a ROS node and instantiate the class.
00019 def main():
00020         '''Create a ROS node and instantiate the class.'''
00021         try:
00022                 rospy.init_node('joy_to_twist')
00023                 jtt = JoyToTwist()
00024                 rospy.spin()
00025         except rospy.ROSInterruptException:
00026                 pass
00027 
00028 if __name__== '__main__':
00029         main()
00030         
00031 


thymio_navigation_driver
Author(s): Stéphane Magnenat and Alexey Gribovskiy
autogenerated on Thu Jan 2 2014 11:17:45