controller_vel_publisher.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # MIT License 2016-2017 (C) Tiryoh<tiryoh@gmail.com>
5 
6 import rospy
7 from geometry_msgs.msg import Twist
8 
9 if __name__ == '__main__':
10  rospy.init_node('vel_publisher')
11  pub = rospy.Publisher('/raspimouse_on_gazebo/diff_drive_controller/cmd_vel', Twist, queue_size=10)
12  try:
13  while not rospy.is_shutdown():
14  vel = Twist()
15  direction = raw_input('w: forward, s: backward, a: left, d: right, q: quit > ')
16  if 'w' in direction:
17  vel.linear.x = 0.18
18  if 's' in direction:
19  vel.linear.x = -0.18
20  if 'a' in direction:
21  vel.angular.z = 90*3.14/180.0
22  if 'd' in direction:
23  vel.angular.z = -90*3.14/180.0
24  if 'q' in direction:
25  break
26  print vel
27  pub.publish(vel)
28  except rospy.ROSInterruptException:
29  pass
30 


raspimouse_control
Author(s): Daisuke Sato , Yuki Watanabe
autogenerated on Mon Jun 10 2019 14:36:49