def _command(self, command: str, *params: str) -> List[str]: """Send a command to the board.""" try: with self._lock: message = " ".join([command] + list(params)) + "\n" self._serial.write(message.encode("utf-8")) results: List[str] = [] while True: line = self.read_serial_line(empty=False) code, param = line.split(None, 1) if code == "+": return results elif code == "-": raise CommunicationError(f"Arduino error: {param}") elif code == ">": results.append(param) elif code == "#": pass # Ignore comment lines else: raise CommunicationError( f"Arduino returned unrecognised response line: {line}", ) except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e
def catch_exceptions(*args, **kwargs): # type: ignore try: return func(*args, **kwargs) except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e
def __init__( self, serial_port: str, serial_class: Type[Serial] = Serial, ): super(SRV4RuggeduinoHardwareBackend, self).__init__( serial_port=serial_port, serial_class=serial_class, ) # Verify that the Ruggeduino has booted count = 0 line = self._command("v") while len(line) == 0: line = self._command("v") count += 1 if count > 25: raise CommunicationError( f"Ruggeduino ({self.serial_port}) is not responding " f"or runs custom firmware.", ) self._version_line = line # Verify the firmware version if int(self.firmware_version) != 1: raise CommunicationError( f"Unexpected firmware version: {self.firmware_version}, " f"expected \"1\".", ) for pin_number in self._digital_pins.keys(): self.set_gpio_pin_mode(pin_number, GPIOPinMode.DIGITAL_INPUT)
def __init__( self, serial_port: str, serial_class: Type[Serial] = Serial, ): super(SBArduinoHardwareBackend, self).__init__( serial_port=serial_port, serial_class=serial_class, ) # Verify that the Arduino has booted count = 0 line = self.read_serial_line(empty=True) while len(line) == 0: line = self.read_serial_line(empty=True) count += 1 if count > 25: raise CommunicationError( f"Arduino ({self.serial_port}) is not responding", ) if line != "# Booted": raise CommunicationError("Arduino Boot Error.") self._version_line = self.read_serial_line() # Verify that the Arduino firmware meets or exceeds the minimum version version_ids = tuple(map(int, self.firmware_version.split("."))) if version_ids < (2019, 6, 0) or len(version_ids) != 3: raise CommunicationError( f"Unexpected firmware version: {self.firmware_version}," f" expected at least: \"2019.6.0\".", )
def _execute_raw_string_command(self, command: str) -> str: """Send a raw string command to the Ruggeduino and return the result.""" try: with self._lock: self._serial.write(command.encode("utf-8")) # Get all the characters in the input buffer return self.read_serial_line(empty=True) except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e
def _read_digital_pin(self, identifier: int) -> bool: """Read the value of a digital pin from the Arduino.""" results = self._command("R", str(identifier)) if len(results) != 1: raise CommunicationError(f"Invalid response from Arduino: {results!r}") result = results[0] if result == "H": return True elif result == "L": return False else: raise CommunicationError(f"Invalid response from Arduino: {result!r}")
def _read_digital_pin(self, identifier: int) -> bool: """Read the value of a digital pin from the Arduino.""" results = self._command("r", identifier) if len(results) != 1: raise CommunicationError( f"Invalid response from Ruggeduino: {results!r}") result = results[0] result_map = {"h": True, "l": False} if result in result_map: return result_map[result] raise CommunicationError( f"Invalid response from Ruggeduino: {result!r}")
def buzz(self, identifier: int, duration: timedelta, frequency: float) -> None: """Queue a pitch to be played.""" if identifier != 0: raise ValueError(f"Invalid piezo identifier {identifier!r}; " f"the only valid identifier is 0.") duration_ms = round(duration / timedelta(milliseconds=1)) if duration_ms > 65535: raise NotSupportedByHardwareError( "Maximum piezo duration is 65535ms.") frequency_int = int(round(frequency)) if frequency_int > 65535: raise NotSupportedByHardwareError( "Maximum piezo frequency is 65535Hz.") data = struct.pack("<HH", frequency_int, duration_ms) try: self._write(CMD_WRITE_PIEZO, data) except USBCommunicationError as e: if e.usb_error.errno == 32: # pipe error raise CommunicationError( f"{e}; are you sending buzz commands to the " f"power board too quickly", ) raise
def _send_command_no_lock(self, command: int, data: Optional[int] = None) -> None: """Send a serial command to the board without acquiring the lock.""" try: message: List[int] = [command] if data is not None: message += [data] bytes_written = self._serial.write(bytes(message)) if len(message) != bytes_written: raise CommunicationError( "Mismatch in command bytes written to serial interface.", ) except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e
def get_ultrasound_pulse( self, trigger_pin_identifier: int, echo_pin_identifier: int, ) -> Optional[timedelta]: """ Get a timedelta for the ultrasound time. Returns None if the sensor times out. """ self._check_ultrasound_pins(trigger_pin_identifier, echo_pin_identifier) results = self._command("T", str(trigger_pin_identifier), str(echo_pin_identifier)) self._update_ultrasound_pin_modes(trigger_pin_identifier, echo_pin_identifier) if len(results) != 1: raise CommunicationError( f"Invalid response from Arduino: {results!r}") result = results[0] microseconds = float(result) if microseconds == 0: # arduino pulseIn() returned 0 which indicates a timeout. return None else: return timedelta(microseconds=microseconds)
def __init__( self, serial_port: str, serial_class: Type[Seriallike] = cast(Type[Seriallike], Serial), # noqa: B008 ) -> None: super(SRV4MotorBoardHardwareBackend, self).__init__( serial_port=serial_port, serial_class=serial_class, baud=1000000, ) # Initialise our stored values for the state. self._state: List[MotorState] = [ MotorSpecialState.BRAKE for _ in range(0, 2) ] self._lock = Lock() # Check we have the correct firmware version. version = self.firmware_version if version != "3": raise CommunicationError( f"Unexpected firmware version: {version}, expected: \"3\".", ) # Brake both of the motors for i, val in enumerate(self._state): self.set_motor_state(i, val)
def __del__(self) -> None: """Clean up device on destruction of object.""" # Brake both of the motors for safety if hasattr(self, "_state"): for i, _ in enumerate(self._state): self.set_motor_state( i, MotorSpecialState.BRAKE, acquire_lock=False, ) try: self._serial.flush() self._serial.close() except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e
def send_command(self, command: int, data: Optional[int] = None) -> None: """Send a serial command to the board.""" message: List[int] = [command] if data is not None: message += [data] bytes_written = self._serial.write(bytes(message)) if len(message) != bytes_written: raise CommunicationError( "Mismatch in command bytes written to serial interface.", )
def read_serial_line(self, empty: bool = False) -> str: """Read a line from the serial interface.""" try: bdata = self._serial.readline() except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e if len(bdata) == 0: if empty: return "" raise CommunicationError( "No response from board. " "Is it correctly powered?", ) ldata = bdata.decode('utf-8') return ldata.rstrip()
def firmware_version(self) -> Optional[str]: """The firmware version of the board.""" self.send_command(CMD_VERSION) firmware_data = self.read_serial_line() model = firmware_data[:5] if model != "MCV4B": raise CommunicationError( f"Unexpected model string: {model}, expected MCV4B.", ) return firmware_data[6:] # Strip model and return version
def singular(self) -> T: """If there is only a single board in the group, return that board.""" num = len(self) if num == 1: return list(self._boards.values())[0] else: name = self._backend_class.board.__name__ raise CommunicationError( f"expected exactly one {name} to be connected, but found {num}", )
def __init__(self, serial_port: str, serial_class: Type[Serial] = Serial) -> None: super(SBArduinoHardwareBackend, self).__init__( serial_port=serial_port, serial_class=serial_class, baud=115200, timeout=timedelta(milliseconds=1250), ) self._digital_pins: Mapping[int, DigitalPinData] = { i: DigitalPinData(mode=GPIOPinMode.DIGITAL_INPUT, state=False) for i in range(2, FIRST_ANALOGUE_PIN) } count = 0 line = self.read_serial_line(empty=True) while len(line) == 0: line = self.read_serial_line(empty=True) count += 1 if count > 25: raise CommunicationError( f"Arduino ({serial_port}) is not responding.") if line != "# Booted": raise CommunicationError("Arduino Boot Error.") self._version_line = self.read_serial_line() if self.firmware_version is not None: version_ids = tuple(map(int, self.firmware_version.split("."))) else: version_ids = (0, 0, 0) if version_ids < (2019, 6, 0): raise CommunicationError( f"Unexpected firmware version: {self.firmware_version},", f" expected at least: \"2019.6.0\".", ) for pin_number in self._digital_pins.keys(): self.set_gpio_pin_mode(pin_number, GPIOPinMode.DIGITAL_INPUT)
def __init__( self, serial_port: str, *, serial_class: Type[Seriallike] = cast(Type[Seriallike], Serial), # noqa: B008 baud: int = 115200, timeout: timedelta = DEFAULT_TIMEOUT, ) -> None: timeout_secs = timeout / timedelta(seconds=1) try: self._serial = serial_class( port=serial_port, baudrate=baud, timeout=timeout_secs, ) except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e
def read_serial_chars(self, size: int = 1) -> str: """Read size bytes from the serial interface.""" if size > self._serial.in_waiting: raise ValueError( f"Tried to read {size} bytes from the serial buffer, " f"only {self._serial.in_waiting} were available.") try: bdata = self._serial.read(size) except SerialTimeoutException as e: raise CommunicationError(f"Serial Timeout Error: {e}") from e except SerialException as e: raise CommunicationError(f"Serial Error: {e}") from e if len(bdata) != size: raise CommunicationError( f"Expected to receive {size} chars, got {len(bdata)} instead.", ) ldata = bdata.decode('utf-8') return ldata.rstrip()
def read_serial_line(self, empty: bool = False) -> str: """Read a line from the serial interface.""" bdata = self._serial.readline() if len(bdata) == 0: if empty: return "" raise CommunicationError( "No response from board. " "Is it correctly powered?", ) ldata = bdata.decode('utf-8') return ldata.rstrip()
def _read_analogue_pin(self, identifier: int) -> float: """Read the value of an analogue pin from the Arduino.""" if identifier >= SBArduinoBoard.FIRST_ANALOGUE_PIN + 4: raise NotSupportedByHardwareError( "Arduino Uno firmware only supports analogue pins 0-3 (IDs 14-17)", ) analogue_pin_num = identifier - 14 results = self._command("A") for result in results: pin_name, reading = result.split(None, 1) if pin_name == f"a{analogue_pin_num}": voltage = (int(reading) / 1024.0) * 5.0 return voltage raise CommunicationError(f"Invalid response from Arduino: {results!r}")
def read_gpio_pin_digital_state(self, identifier: int) -> bool: """Read the digital state of the GPIO pin.""" if identifier >= FIRST_ANALOGUE_PIN: raise NotSupportedByHardwareError( "Digital functions not supported on analogue pins", ) if self._digital_pins[identifier].mode not in ( GPIOPinMode.DIGITAL_INPUT, GPIOPinMode.DIGITAL_INPUT_PULLUP, ): raise ValueError( f"Pin {identifier} mode needs to be DIGITAL_INPUT_*" f"in order to read the digital state.") results = self._command("R", str(identifier)) if len(results) != 1: raise CommunicationError( f"Invalid response from Arduino: {results!r}") result = results[0] if result == "H": return True elif result == "L": return False else: raise CommunicationError( f"Invalid response from Arduino: {result!r}")
def read_gpio_pin_analogue_value(self, identifier: int) -> float: """Read the analogue voltage of the GPIO pin.""" if identifier < FIRST_ANALOGUE_PIN: raise NotSupportedByHardwareError( "Analogue functions not supported on digital pins", ) if identifier >= FIRST_ANALOGUE_PIN + 4: raise NotSupportedByHardwareError( f"Arduino Uno firmware only supports analogue pins 0-3 (IDs 14-17)", ) analogue_pin_num = identifier - 14 results = self._command("A") for result in results: pin_name, reading = result.split(None, 1) if pin_name == f"a{analogue_pin_num}": voltage = (int(reading) / 1024.0) * 5.0 return voltage raise CommunicationError(f"Invalid response from Arduino: {results!r}")
def get_ultrasound_distance( self, trigger_pin_identifier: int, echo_pin_identifier: int, ) -> Optional[float]: """Get a distance in metres.""" self._check_ultrasound_pins(trigger_pin_identifier, echo_pin_identifier) results = self._command("U", str(trigger_pin_identifier), str(echo_pin_identifier)) self._update_ultrasound_pin_modes(trigger_pin_identifier, echo_pin_identifier) if len(results) != 1: raise CommunicationError(f"Invalid response from Arduino: {results!r}") result = results[0] millimetres = float(result) if millimetres == 0: # arduino pulseIn() returned 0 which indicates a timeout. return None else: return millimetres / 1000.0