<launch>
<node name="joy_node" pkg="joy" type="joy_node" />
<node name="joy_to_cmd_vel" pkg="joypad_bridge" type="joy_to_cmd_vel.py"/>
- <node name="cmd_vel_transmitter" pkg="joypad_bridge" type="cmd_vel_transmitter.py"/>
+ <node name="cmd_vel_transmitter" pkg="joypad_bridge" type="cmd_vel_transmitter.py" output="screen"/>
</launch>
import rospy, serial, struct, time
from geometry_msgs.msg import Twist
+from serial import SerialException
ser = serial.Serial(
- port='/dev/ttyUSB0',
baudrate=115200,
parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
bytesize=serial.EIGHTBITS,
rtscts=False)
-current_millis = 0
-last_millis = 0
-
def callback(data):
- global current_millis
- global last_millis
- #da fixare
linear = -data.linear.x
- angular = -data.angular.z
- last_millis = current_millis
- current_millis = int(round(time.time() * 1000))
+ angular = -data.angular.z #da fixare?
rospy.loginfo('I heard %f %f', linear, angular)
- if (1):
- msg_output = struct.pack('<ff', linear, angular)
- ser.write(msg_output)
- ser.flush()
+ msg_output = struct.pack('<ff', linear, angular)
+ ser.write(msg_output)
+ ser.flush()
def listener():
-
+ while(ser.is_open == False):
+ try:
+ ser.port = '/dev/ttyUSB0'
+ ser.open()
+ except SerialException:
+ print('couldnt open /dev/ttyUSB0')
+ time.sleep(2)
+
+ print('ttyUSB0 opened')
rospy.init_node('cmd_vel_transmitter', anonymous=True)
rospy.Subscriber('/cmd_vel', Twist, callback)
import serial, struct, time
+from serial import SerialException
+
ser = serial.Serial(
- port='/dev/ttyUSB0',
baudrate=115200,
- parity=serial.PARITY_ODD,
+ parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
bytesize=serial.EIGHTBITS,
rtscts=False)
+
+while (ser.is_open == False):
+ try:
+ ser.port = '/dev/ttyUSB0'
+ ser.open()
+ except SerialException:
+ print("couldn't open ttyUSB0, check the connection")
+ time.sleep(2)
+print("yay")
+
+
pid_select = float(input("Enter 1 for left tuning, 2 for right tuning, 3 for cross tuning: "))
if (pid_select == 3):
pid_lin_vel = float(input("Enter the linear velocity setpoint: "))
-import serial, struct, time
+import time, serial, struct
+from serial import SerialException
ser = serial.Serial(
- port='/dev/ttyUSB0',
baudrate=115200,
- parity=serial.PARITY_ODD,
+ parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
bytesize=serial.EIGHTBITS,
rtscts=False)
+while (ser.is_open == False):
+ try:
+ ser.port = '/dev/ttyUSB0'
+ ser.open()
+ except SerialException:
+ print("couldn't open ttyUSB0, check the connection")
+ time.sleep(2)
+
+print("port open")
while 1:
ser.reset_input_buffer()
-import serial, struct, time
+import time, serial, struct
+from serial import SerialException
+
ser = serial.Serial(
- port='/dev/ttyUSB0',
baudrate=115200,
- parity=serial.PARITY_ODD,
+ parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
bytesize=serial.EIGHTBITS,
rtscts=False)
+while (ser.is_open == False):
+ try:
+ ser.port = '/dev/ttyUSB0'
+ ser.open()
+ except SerialException:
+ print("couldn't open ttyUSB0, check the connection")
+ time.sleep(2)
+
+print("open port")
ang_vel_cmd = 0
lin_vel_cmd = 1
while 1:
ser.write(msg_output_buffer)
print(ang_vel_cmd)
print(lin_vel_cmd)
-# ang_vel_cmd = ang_vel_cmd - 1
-# lin_vel_cmd = lin_vel_cmd - 1
ser.reset_output_buffer()
time.sleep(3)
import serial, struct, time, signal, sys
from datetime import datetime
+from serial import SerialException
ser = serial.Serial(
- port='/dev/ttyUSB0',
baudrate=115200,
- parity=serial.PARITY_ODD,
+ parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
bytesize=serial.EIGHTBITS,
rtscts=False)
+while (ser.is_open == False):
+ try:
+ ser.port = '/dev/ttyUSB0'
+ ser.open()
+ except SerialException:
+ print("couldn't open ttyUSB0, check the connection")
+ time.sleep(2)
+print("yay")
+
def signal_handler(sig, frame):
print('Logging stopped')
print('Info logged on ' + file_name)