6 from geometry_msgs.msg
import Twist
7 from std_msgs.msg
import Float32
10 def __init__(self,linear_scaling,angular_scaling,keyboard=False):
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,
25 rospy.logdebug(
"\tangular:")
26 rospy.logdebug(
"\t\tx:%f,y:%f,z:%f"%(data.angular.x,
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
39 self.left_msg.data = data.linear.x
40 self.right_msg.data = data.angular.z
43 rospy.logdebug(
"\tleft:%f, right:%f"%(self.left_msg.data,
49 if __name__ ==
'__main__':
51 rospy.init_node(
'twist2drive', anonymous=
True)
55 linear_scaling = rospy.get_param(
'~linear_scaling',0.2)
57 angular_scaling = rospy.get_param(
'~angular_scaling',0.05)
59 rospy.loginfo(
"Linear scaling=%f, Angular scaling=%f"%(linear_scaling,angular_scaling))
62 key =
'--keyboard' in sys.argv
63 node=
Node(linear_scaling,angular_scaling,keyboard=key)
66 node.left_pub = rospy.Publisher(
"left_cmd",Float32,queue_size=10)
67 node.right_pub = rospy.Publisher(
"right_cmd",Float32,queue_size=10)
72 rospy.Subscriber(
"cmd_vel",Twist,node.callback)
76 except rospy.ROSInterruptException:
def __init__(self, linear_scaling, angular_scaling, keyboard=False)