twist2thrust.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # license removed for brevity
3 
4 import sys
5 import rospy
6 from geometry_msgs.msg import Twist
7 from std_msgs.msg import Float32
8 
9 class Node():
10  def __init__(self,linear_scaling,angular_scaling,keyboard=False):
11  self.linear_scaling = linear_scaling
12  self.angular_scaling = angular_scaling
13  self.left_pub = None
14  self.right_pub = None
15  self.left_msg =None
16  self.right_msg =None
17  self.keyboard = keyboard
18 
19  def callback(self,data):
20  rospy.logdebug("RX: Twist "+rospy.get_caller_id())
21  rospy.logdebug("\tlinear:")
22  rospy.logdebug("\t\tx:%f,y:%f,z:%f"%(data.linear.x,
23  data.linear.y,
24  data.linear.z))
25  rospy.logdebug("\tangular:")
26  rospy.logdebug("\t\tx:%f,y:%f,z:%f"%(data.angular.x,
27  data.angular.y,
28  data.angular.z))
29  # scaling factors
30  linfac = self.linear_scaling
31  angfac = self.angular_scaling
32 
33  if self.keyboard:
34  self.left_msg.data = data.linear.x
35  self.right_msg.data = data.linear.x
36  self.left_msg.data += -1*data.angular.z
37  self.right_msg.data += data.angular.z
38  else:
39  self.left_msg.data = data.linear.x
40  self.right_msg.data = data.angular.z
41 
42  rospy.logdebug("TX ")
43  rospy.logdebug("\tleft:%f, right:%f"%(self.left_msg.data,
44  self.right_msg.data))
45  self.left_pub.publish(self.left_msg)
46  self.right_pub.publish(self.right_msg)
47 
48 
49 if __name__ == '__main__':
50 
51  rospy.init_node('twist2drive', anonymous=True)
52 
53  # ROS Parameters
54  # Scaling from Twist.linear.x to (left+right)
55  linear_scaling = rospy.get_param('~linear_scaling',0.2)
56  # Scaling from Twist.angular.z to (right-left)
57  angular_scaling = rospy.get_param('~angular_scaling',0.05)
58 
59  rospy.loginfo("Linear scaling=%f, Angular scaling=%f"%(linear_scaling,angular_scaling))
60 
61 
62  key = '--keyboard' in sys.argv
63  node=Node(linear_scaling,angular_scaling,keyboard=key)
64 
65  # Publisher
66  node.left_pub = rospy.Publisher("left_cmd",Float32,queue_size=10)
67  node.right_pub = rospy.Publisher("right_cmd",Float32,queue_size=10)
68  node.left_msg = Float32()
69  node.right_msg = Float32()
70 
71  # Subscriber
72  rospy.Subscriber("cmd_vel",Twist,node.callback)
73 
74  try:
75  rospy.spin()
76  except rospy.ROSInterruptException:
77  pass
def __init__(self, linear_scaling, angular_scaling, keyboard=False)
Definition: twist2thrust.py:10
def callback(self, data)
Definition: twist2thrust.py:19


vmrc_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Sun Feb 17 2019 03:14:16