]> git.leonardobizzoni.com Git - pioneer-stm32/commitdiff
fix python scripts, now looping till we can open serial port
authorFederica Di Lauro <federicadilauro1998@gmail.com>
Tue, 28 Jan 2020 09:20:19 +0000 (10:20 +0100)
committerFederica Di Lauro <federicadilauro1998@gmail.com>
Tue, 28 Jan 2020 09:20:19 +0000 (10:20 +0100)
utils/catkin_ws/joypad.launch
utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py
utils/pid_tuning/pid_tuning.py
utils/py_serial_examples/receive.py
utils/py_serial_examples/transmit.py
utils/ticks_calibration/ticks_logger.py

index 69f8ec651ed8719c3ee96a9e44a87fb05eb87ff6..e3765a850bc113f68e2acbf6eb13d6aa9100bae7 100644 (file)
@@ -1,5 +1,5 @@
 <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>
index ae2859cea12fd6bbe659e96a20ed63ddd8da740b..381ae56b8095e263ee77c059d3bd1b46900f9d1e 100755 (executable)
@@ -2,36 +2,35 @@
 
 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)
index 21af19a35aeb5b0270c434dabcaabc7e007b9a06..eeaf5a733ee6a344af071230cde07d85ed81203a 100644 (file)
@@ -1,11 +1,23 @@
 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: "))
index 182e3f4e78e13cd0f7c0d28ddfdee12e135d051b..94fc687fe5c8f1ce98edc7a06e22b3b7cc527c4a 100644 (file)
@@ -1,11 +1,20 @@
-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()
index ce9df64be3768adde104b47a541d91a7b4feecd5..63f9bc4503ec67d3a9c843f8568bb9b9bcb328d9 100644 (file)
@@ -1,11 +1,21 @@
-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:
@@ -13,7 +23,5 @@ 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)
index 341d8726130cec093a1eeb0434a9954549887a6c..4c375f30914240c545ba47d3f501a8288ba26c48 100644 (file)
@@ -1,14 +1,23 @@
 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)