Skip to content

Commit

Permalink
pymavlink: workaround a kernel baudrate set bug
Browse files Browse the repository at this point in the history
sometimes some Linux kernels don't set the baudrate correctly
  • Loading branch information
Andrew Tridgell committed May 16, 2014
1 parent 21c936d commit 9860922
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion pymavlink/mavutil.py
Original file line number Diff line number Diff line change
Expand Up @@ -672,20 +672,28 @@ def __init__(self, device, baud=115200, autoreconnect=False, source_system=255):
self.baud = baud
self.device = device
self.autoreconnect = autoreconnect
self.port = serial.Serial(self.device, self.baud, timeout=0,
# we rather strangely set the baudrate initially to 1200, then change to the desired
# baudrate. This works around a kernel bug on some Linux kernels where the baudrate
# is not set correctly
self.port = serial.Serial(self.device, 1200, timeout=0,
dsrdtr=False, rtscts=False, xonxoff=False)
try:
fd = self.port.fileno()
set_close_on_exec(fd)
except Exception:
fd = None
self.set_baudrate(self.baud)
mavfile.__init__(self, fd, device, source_system=source_system)
self.rtscts = False

def set_rtscts(self, enable):
'''enable/disable RTS/CTS if applicable'''
self.port.setRtsCts(enable)
self.rtscts = enable

def set_baudrate(self, baudrate):
'''set baudrate'''
self.port.setBaudrate(baudrate)

def close(self):
self.port.close()
Expand Down

0 comments on commit 9860922

Please sign in to comment.