controller_vel_publisher.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 # MIT License 2016-2017 (C) Tiryoh<tiryoh@gmail.com>
00005 
00006 import rospy
00007 from geometry_msgs.msg import Twist
00008 
00009 if __name__ == '__main__':
00010     rospy.init_node('vel_publisher')
00011     pub = rospy.Publisher('/raspimouse_on_gazebo/diff_drive_controller/cmd_vel', Twist, queue_size=10)
00012     try:
00013         while not rospy.is_shutdown():
00014             vel = Twist()
00015             direction = raw_input('w: forward, s: backward, a: left, d: right, q: quit > ')
00016             if 'w' in direction:
00017                 vel.linear.x = 0.18
00018             if 's' in direction:
00019                 vel.linear.x = -0.18
00020             if 'a' in direction:
00021                 vel.angular.z = 90*3.14/180.0
00022             if 'd' in direction:
00023                 vel.angular.z = -90*3.14/180.0
00024             if 'q' in direction:
00025                 break
00026             print vel
00027             pub.publish(vel)
00028     except rospy.ROSInterruptException:
00029             pass
00030 


raspimouse_control
Author(s): Daisuke Sato , Yuki Watanabe
autogenerated on Thu Jun 6 2019 19:54:26