emdbg.debug.px4.device

  1# Copyright (c) 2023, Auterion AG
  2# SPDX-License-Identifier: BSD-3-Clause
  3
  4from __future__ import annotations
  5from . import utils
  6from dataclasses import dataclass
  7from .base import Base
  8from functools import cached_property
  9from pathlib import Path
 10import re, time
 11import rich.box
 12from rich.text import Text
 13from rich.table import Table
 14
 15
 16class Device(Base):
 17    """
 18    Accessors for the state of ARM Cortex-M CPU, STM32 identifiers, uptime, and
 19    NuttX kernel internals.
 20    """
 21    _HRT_CNT = 0x4001_0424
 22    _SCS_ICTR = 0xE000_E004
 23    _SCB_CPUID = 0xE000_ED00
 24    _SCB_VTOR = 0xE000_ED08
 25    _SCS_SHPR = 0xE000_ED18
 26    _NVIC_ISER = 0xE000_E100
 27    _NVIC_ISPR = 0xE000_E200
 28    _NVIC_IABR = 0xE000_E300
 29    _NVIC_IPR = 0xE000_E400
 30
 31    # Try them all until one of them does not return zero
 32    _DBG_IDCODE = [0xE004_2000, 0x5C00_1000]
 33
 34    @cached_property
 35    def _IDCODE_REVISION(self):
 36        return {
 37            0x1000: "A",
 38            0x1001: "Z",
 39            0x1003: "Y",
 40            0x1007: "4",
 41            0x2001: "X",
 42            0x2003: "Y",
 43        }.get(self.rev, "")
 44
 45    @cached_property
 46    def _IDCODE_DEVICE(self):
 47        return {
 48            0x0415: "STM32L47/L48xx",
 49            0x0451: "STM32F76xx, STM32F77xx",
 50            0x0450: "STM32H742, STM32H743/753, STM32H750",
 51            0x0483: "STM32H723/733, STM32H725/735, STM32H730",
 52        }.get(self.devid, "Unknown")
 53
 54    @cached_property
 55    def _GPIOS(self):
 56        return {
 57            0x0415: list(range(0x4800_0000, 0x4800_2000, 0x400)),
 58            # FMUv5x/v6x don't use ports J and K
 59            0x0451: list(range(0x4002_0000, 0x4002_2001, 0x400)),
 60            0x0450: list(range(0x5802_0000, 0x5802_2001, 0x400)),
 61            0x0483: list(range(0x5802_0000, 0x5802_2C01, 0x400)),
 62        }.get(self.devid, [])
 63
 64    @cached_property
 65    def _SYSTEM_MEMORIES(self):
 66        mems = [(0xE000_0000, 0x10_0000)]
 67        mems += {
 68            0x0415: [(0x1FFF_7500, 0x100)],
 69            0x0451: [(0x1FF0_F420, 0x100), (0x1FFF_7B00, 0x100)],
 70            **dict.fromkeys([0x0450, 0x0483],
 71                    [(0x1FF1_E800, 0x100), (0x58000524, 4)])
 72        }.get(self.devid, [])
 73        return mems
 74
 75    @cached_property
 76    def _PERIPHERALS(self):
 77        if self._SVD_FILE is None: return []
 78        from cmsis_svd.parser import SVDParser
 79        device = SVDParser.for_xml_file(self._SVD_FILE).get_device()
 80        registers = [(per.base_address + r.address_offset,
 81                      per.base_address + r.address_offset + r.size//8)
 82                     for per in device.peripherals for r in per.registers]
 83        registers.sort()
 84        ranges = []
 85        cluster = 512
 86        current = registers[0]
 87        for (regl, regh) in registers[1:]:
 88            if (current[1] + cluster) > regh:
 89                current = (current[0], regh)
 90            else:
 91                ranges.append(current)
 92                current = (regl, regh)
 93        ranges.append(current)
 94        return [(r[0], r[1] - r[0]) for r in ranges]
 95
 96    @cached_property
 97    def _MEMORIES(self):
 98        mems = {
 99            0x0415: [
100                (0x1000_0000, 0x20000), # SRAM2
101                (0x2000_0000, 0x20000), # SRAM1
102            ],
103            0x0451: [
104                # (0x0000_0000, 0x04000), # ITCM
105                (0x2000_0000, 0x80000), # DTCM, SRAM1, SRAM2
106            ],
107            **dict.fromkeys([0x0450, 0x0483], [
108                # (0x0000_0000, 0x10000), # ITCM
109                (0x2000_0000, 0x20000), # DTCM
110                (0x2400_0000, 0x80000), # AXI_SRAM
111                (0x3000_0000, 0x48000), # SRAM1, SRAM2, SRAM3
112                (0x3800_0000, 0x10000), # SRAM4
113                (0x3880_0000, 0x01000), # Backup SRAM
114                (0x5C00_1000, 4),       # IDCODE
115            ]),
116        }.get(self.devid, [])
117        mems += self._PERIPHERALS
118        mems += self._SYSTEM_MEMORIES
119        return sorted(mems)
120
121    @cached_property
122    def _SVD_FILE(self):
123        return {
124            # 0x0415: Path(__file__).parents[1] / "data/STM32L4x6.svd",
125            0x0451: Path(__file__).parents[1] / "data/STM32F765.svd",
126            0x0450: Path(__file__).parents[1] / "data/STM32H753.svd",
127            # 0x0483: Path(__file__).parents[1] / "data/STM32H7x3.svd",
128        }.get(self.devid)
129
130    @dataclass
131    class Gpio:
132        port: str
133        index: int
134        moder: int
135        otyper: int
136        speedr: int
137        pupdr: int
138        idr: int
139        odr: int
140        lockr: int
141        afr: int
142
143    @dataclass
144    class Irq:
145        index: int
146        """Index of the IRQ starting at zero"""
147        handler: "gdb.Block"
148        """Function handler of the IRQ"""
149        priority: int
150        """Priority of the IRQ"""
151        is_enabled: bool
152        """Is interrupt enabled"""
153        is_pending: bool
154        """Is interrupt pending"""
155        is_active: bool
156        """Is interrupt active"""
157
158    @dataclass
159    class IrqNuttX(Irq):
160        arg: "gdb.Value"
161        """Optional argument passed to the IRQ handler"""
162
163    def __init__(self, gdb):
164        super().__init__(gdb)
165        self.architecture = self._arch.name()
166        self._hrt_counter = self.addr_ptr(self._HRT_CNT, "uint16_t")
167
168    @cached_property
169    def _hrt_base(self):
170        return self.lookup_static_symbol_in_function_ptr("base_time", "hrt_absolute_time")
171
172    def _read_bits(self, base, index, size):
173        shift = ((index * size) % 64)
174        offset = (index * size) // 64
175        mask = ((1 << size) - 1) << shift
176        bits = self.read_memory(base + offset, 8).cast("Q")[0]
177        return (bits & mask) >> shift
178
179    def _priority(self, index):
180        if index == -15: return -3
181        if index == -14: return -2
182        if index == -13: return -1
183        if index < 0: return self._read_bits(self._SCS_SHPR, index + 16, 8)
184        return self._read_bits(self._NVIC_IPR, index, 8)
185
186    def _enabled(self, index):
187        # if index < 0: return self._read_bits1(self._SCS_, index);
188        return self._read_bits(self._NVIC_ISER, index, 1)
189
190    def _pending(self, index):
191        return self._read_bits(self._NVIC_ISPR, index, 1)
192
193    def _active(self, index):
194        return self._read_bits(self._NVIC_IABR, index, 1)
195
196    @cached_property
197    def uptime(self) -> int:
198        """The uptime in microseconds as read from the NuttX high-resolution timer (HRT)"""
199        if self._hrt_base is None: return 0
200        return int(self._hrt_base.dereference() + self._hrt_counter.dereference())
201
202    @cached_property
203    def max_interrupts(self) -> int:
204        """Maximum number of interrupts implemented on this device"""
205        return 32 * (self.read_uint(self._SCS_ICTR, 4) + 1)
206
207    @cached_property
208    def vector_table(self) -> list[Irq]:
209        """The vector table as stored inside the SCB->VTOR"""
210        # SCS = 0xE000E000, SCB = 0xE000ED00, SCB->VTOR = 0xE000ED08
211        # TODO: Cortex-M0 has no VTOR, Cortex-M0+ has one if implemented
212        vtor = self._gdb.Value(self._SCB_VTOR).cast(self.uint32.pointer())
213        vtor = vtor.dereference().cast(self.uint32.pointer())
214        entries = []
215        for ii in range(self.max_interrupts):
216            ii -= 16
217            entries.append(self.Irq(ii, self.block(vtor[ii+16]), self._priority(ii),
218                                    self._enabled(ii), self._pending(ii), self._active(ii)))
219        return entries
220
221    @cached_property
222    def vector_table_nuttx(self) -> dict[int, IrqNuttX]:
223        """
224        The index, handler and argument of the NuttX interrupt table if the
225        handler is not empty and is not `irq_unexpected_isr`.
226        """
227        g_irqvector = self._gdb.lookup_global_symbol("g_irqvector")
228        vectors = {}
229        for ii, vector in enumerate(utils.gdb_iter(g_irqvector)):
230            if handler := vector["handler"]:
231                block = self.block(handler)
232                if block.function and block.function.name == "irq_unexpected_isr":
233                    continue
234                ii -= 16
235                vectors[ii] = self.IrqNuttX(ii, block, self._priority(ii),
236                                            self._enabled(ii), self._pending(ii),
237                                            self._active(ii), vector["arg"])
238        return vectors
239
240    @property
241    def gpios(self) -> list[Gpio]:
242        """List of GPIOs as read from the device."""
243        result = []
244        for jj, gper_addr in enumerate(self._GPIOS):
245            port = chr(ord("A") + jj)
246            gper = self.read_memory(gper_addr, 0x28).cast("I")
247            for ii in range(16):
248                _1v = lambda index: (gper[index] >> ii) & 0x1
249                _2v = lambda index: (gper[index] >> ii*2) & 0x3
250                moder, speedr, pupdr = _2v(0), _2v(2), _2v(3)
251                otyper, idr, odr, lockr = _1v(1), _1v(4), _1v(5), _1v(7)
252                afr = ((gper[9] << 32 | gper[8]) >> ii*4) & 0xf
253                g = self.Gpio(port, ii, moder, otyper, speedr, pupdr, idr, odr, lockr, afr)
254                result.append(g)
255        return result
256
257    def coredump(self, memories: list[tuple[int, int]] = None, with_flash: bool = False) -> tuple[str, int]:
258        """
259        Reads the memories and registers and returns them as a formatted string
260        that is compatible with CrashDebug (see `emdbg.debug.crashdebug`).
261
262        :param memories: list of memory ranges (start, size) to dump
263        :param with_flash: also dump the entire non-volatile storage
264        :return: coredump formatted as string and coredump size
265        """
266        if memories is None:
267            memories = self._MEMORIES
268        if with_flash and self.flash_size:
269            memories += [(0x0800_0000, self.flash_size)]
270        lines = []
271        total_size = 0
272        for addr, size in memories:
273            try:
274                data = self.read_memory(addr, size).cast("I")
275                total_size += size
276            except Exception as e:
277                print(f"Failed to read whole range [{addr:#x}, {addr+size:#x}]! {e}")
278                data = []
279                for offset in range(0, size, 4):
280                    try:
281                        data.append(self.read_memory(addr + offset, 4).cast("I")[0])
282                        total_size += 4
283                    except Exception as e:
284                        print(f"Failed to read uint32_t {addr+offset:#x}! {e}")
285                        data.append(0)
286                        continue
287            for ii, values in enumerate(utils.chunks(data, 4, 0)):
288                values = (hex(v & 0xffffffff) for v in values)
289                lines.append(f"{hex(addr + ii * 16)}: {' '.join(values)}")
290
291        for name, value in self.registers.items():
292            if re.match(r"d\d+", name):
293                lines.append(f"{name:<28} {float(value):<28} (raw {value & 0xffffffffffffffff:#x})")
294            elif re.match(r"s\d+", name):
295                lines.append(f"{name:<28} {float(value):<28} (raw {value & 0xffffffff:#x})")
296            else:
297                lines.append(f"{name:<28} {hex(value & 0xffffffff):<28} {int(value)}")
298
299        return "\n".join(lines), total_size
300
301    @cached_property
302    def cpuid(self) -> int:
303        """The SCB->CPUID value"""
304        return self.read_uint(self._SCB_CPUID, 4)
305
306    @cached_property
307    def idcode(self) -> int:
308        """The STM32-specific DBG->IDCODE value"""
309        for addr in self._DBG_IDCODE:
310            if idcode := (self.read_uint(addr, 4) & 0xffff0fff):
311                return idcode
312        return 0
313
314    @cached_property
315    def flash_size(self) -> int:
316        """The FLASH size in bytes"""
317        addr = {
318            0x0415: 0x1FFF_75E0,
319            0x0451: 0x1FF0_F442,
320            0x0450: 0x1FF1_E880,
321            0x0483: 0x1FF1_E880,
322        }.get(self.devid)
323        if addr is None: return 0
324        return self.read_uint(addr, 2) * 1024
325
326    @cached_property
327    def line(self) -> str:
328        """The device family and name"""
329        if self.devid == 0x0483:
330            return self.read_string(0x1FF1_E8C0, length=4)[::-1]
331        return self._IDCODE_DEVICE
332
333    @cached_property
334    def uid(self) -> int:
335        """The device's unique identifier as a big integer"""
336        addr = {
337            0x0415: 0x1FFF_7590,
338            0x0451: 0x1FF0_F420,
339            0x0450: 0x1FF1_E800,
340            0x0483: 0x1FF1_E800,
341        }.get(self.devid)
342        if addr is None: return 0
343        return int.from_bytes(self.read_memory(addr, 3*4).tobytes(), "little")
344
345    @cached_property
346    def package(self) -> str:
347        """The device package"""
348
349        if self.devid == 0x0415:
350            return {
351                0b00000: "LQFP64",
352                0b00010: "LQFP100",
353                0b00011: "UFBGA132",
354                0b00100: "LQFP144, UFBGA144, WLCSP72, WLCSP81 or WLCSP86",
355                0b10000: "UFBGA169, WLCSP115",
356                0b10001: "WLCSP100",
357            }.get(self.read_uint(0x1FFF_7500, 1) & 0x1f, "Reserved")
358        if self.devid == 0x0451:
359            return {
360                0b111: "LQFP208 or TFBGA216",
361                0b110: "LQFP208 or TFBGA216",
362                0b101: "LQFP176",
363                0b100: "LQFP176",
364                0b011: "WLCSP180",
365                0b010: "LQFP144 ",
366                0b001: "LQFP100",
367            }.get(self.read_uint(0x1FFF_7BF1, 1) & 0x7, "Reserved")
368        if self.devid == 0x0450:
369            return {
370                0b0000: "LQFP100",
371                0b0010: "TQFP144",
372                0b0101: "TQFP176/UFBGA176",
373                0b1000: "LQFP208/TFBGA240",
374            }.get(self.read_uint(0x58000524, 1) & 0xf, "All pads enabled")
375        if self.devid == 0x0483:
376            return {
377                0b0000: "VFQFPN68 Industrial",
378                0b0001: "LQFP100 Legacy / TFBGA100 Legacy",
379                0b0010: "LQFP100 Industrial",
380                0b0011: "TFBGA100 Industrial",
381                0b0100: "WLCSP115 Industrial",
382                0b0101: "LQFP144 Legacy",
383                0b0110: "UFBGA144 Legacy",
384                0b0111: "LQFP144 Industrial",
385                0b1000: "UFBGA169 Industrial",
386                0b1001: "UFBGA176+25 Industrial",
387                0b1010: "LQFP176 Industrial",
388            }.get(self.read_uint(0x58000524, 1) & 0xf, "All pads enabled")
389        return "?"
390
391    @cached_property
392    def devid(self) -> int:
393        """The STM32-specific device id part of DBG->IDCODE"""
394        return self.idcode & 0xfff
395
396    @cached_property
397    def rev(self) -> int:
398        """The STM32-specific revision part of DBG->IDCODE"""
399        return self.idcode >> 16
400
401
402def discover(gdb) -> Table:
403    """
404    Reads the device identifier registers and outputs a human readable string if possible.
405    :return: description string
406    """
407    dev = Device(gdb)
408    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
409    table.add_column("Device")
410    table.add_column("Revision")
411    table.add_column("Flash")
412    table.add_column("Package")
413    table.add_column("UID")
414    table.add_row(f"{dev.devid:#4x}: {dev.line}",
415                  f"{dev.rev:#4x}: rev {dev._IDCODE_REVISION}",
416                  f"{dev.flash_size//1024}kB", dev.package,
417                  f"{dev.uid:x}")
418    return table
419
420
421def all_registers(gdb) -> dict[str, int]:
422    """Return a dictionary of register name and values"""
423    return Device(gdb).registers
424
425
426def all_registers_as_table(gdb, columns: int = 3) -> Table:
427    """
428    Format the Cortex-M CPU+FPU registers and their values into a simple table.
429
430    :param columns: The number of columns to spread the registers across.
431    """
432    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
433    table.add_column("Name")
434    table.add_column("Hexadecimal", justify="right")
435    table.add_column("Decimal", justify="right")
436    table.add_column("Binary", justify="right")
437    for reg, value in all_registers(gdb).items():
438        table.add_row(reg, f"{value:x}", str(value), f"{value:b}")
439    return table
440
441
442def vector_table(gdb) -> dict[int, Device.IrqNuttX]:
443    """Return a dictionary of NuttX interrupt numbers and their handlers with arguments"""
444    return Device(gdb).vector_table_nuttx
445
446
447def vector_table_as_table(gdb, columns: int = 1) -> Table:
448    """
449    Format the NuttX interrupts and their handlers with arguments into a simple table.
450
451    :param columns: The number of columns to spread the interrupts across.
452    """
453    def _fname(block):
454        count = 0
455        while block and block.function is None:
456            block = block.superblock
457            count += 1
458        if block.function:
459            return f"{block.function.name} {'^' * count}"
460        return f"{block} ?"
461
462    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
463    table.add_column("IRQ", justify="right")
464    table.add_column("EPA")
465    table.add_column("Prio")
466    table.add_column("Address")
467    table.add_column("Function")
468    table.add_column("Argument")
469    for idx, irq in vector_table(gdb).items():
470        table.add_row(str(idx),
471                      ("e" if irq.is_enabled else " ") +
472                      ("p" if irq.is_pending else " ") +
473                      ("a" if irq.is_active else " "),
474                      f"{irq.priority:x}", hex(irq.handler.start),
475                      _fname(irq.handler), str(irq.arg) or "",
476                      style="bold blue" if irq.is_active else None)
477    return table
478
479
480def coredump(gdb, memories: list[tuple[int, int]] = None,
481             with_flash: bool = False, filename: Path = None):
482    """
483    Dumps the memories and register state into a file.
484
485    :param memories: List of (addr, size) tuples that describe which memories to dump.
486    :param with_flash: Also dump the entire non-volatile storage.
487    :param filename: Target filename, or `coredump_{datetime}.txt` by default.
488    """
489    if filename is None:
490        filename = utils.add_datetime("coredump.txt")
491    print("Starting coredump...", flush=True)
492    start = time.perf_counter()
493    output, size = Device(gdb).coredump(memories, with_flash)
494    Path(filename).write_text(output)
495    end = time.perf_counter()
496    print(f"Dumped {size//1000}kB in {(end - start):.1f}s ({int(size/((end - start)*1000))}kB/s)")
497
498
499def all_gpios_as_table(gdb, pinout: dict[str, tuple[str, str]] = None,
500                       fn_filter = None, sort_by = None, columns: int = 2) -> Table:
501    """
502    Reads the GPIO peripheral space and prints a table of the individual pin
503    configuration, input/output state and alternate function. If a pinout is
504    provided, the pins will be matched with their names and functions.
505
506    Config: Condensed view with omitted defaults.
507        MODER:  IN=Input, OUT=Output, ALT=Alternate Function, AN=Analog,
508        OTYPER: +OD=OpenDrain, (+PP=PushPull omitted),
509        PUPDR:  +PU=PullUp, +PD=PullDown, (+FL=Floating omitted),
510        SPEEDR: +M=Medium, +H=High, +VH=Very High, (+L=Low omitted).
511
512    Input (IDR), Output (ODR): _=Low, ^=High
513        Input only shown for IN, OUT, and ALT.
514        Output only shown for OUT.
515
516    Alternate Function (AFR): only shown when config is ALT.
517        Consult the datasheet for device-specific mapping.
518
519    :param pinout: A map of port+index -> (name, function).
520    :param pin_filter: A filter function that gets passed the entire row as a
521                       list and returns `True` if row is accepted.
522    :param sort_by: The name of the column to sort by: default is `PIN`.
523    :param columns: The number of columns to spread the GPIO table across.
524    """
525    rows = []
526    for gpio in Device(gdb).gpios:
527        name = f"{gpio.port}{gpio.index}"
528        if pinout is not None:
529             list(pinout.get(name, [""]*2))
530        config = "".join([["IN", "OUT", "ALT", "AN"][gpio.moder],
531                          ["", "+OD"][gpio.otyper],
532                          ["", "+PU", "+PD", "+!!"][gpio.pupdr],
533                          ["", "+M", "+H", "+VH"][gpio.speedr],
534                          ["", "+L"][gpio.lockr]])
535        idr = "" if gpio.moder == 3 else ["_", "^"][gpio.idr]
536        odr = ["_", "^"][gpio.odr] if gpio.moder == 1 else ""
537        afr = str(gpio.afr) if gpio.moder == 2 else ""
538        row = [name, config, idr, odr, afr]
539        if pinout is not None:
540            row += list(pinout.get(name, [""]*2))
541        if fn_filter is None or fn_filter(row):
542            rows.append(row)
543    if sort_by is not None:
544        def _sort(row):
545            pinf = ord(row[0][0]) * 100 + int(row[0][1:])
546            if sort_by == 0: return pinf
547            if sort_by == 4: return -1 if row[4] == "" else row[4]
548            if sort_by == 5: return (row[5], row[6], pinf)
549            if sort_by == 6: return (row[6], row[5], pinf)
550            return row[sort_by]
551        rows.sort(key=_sort)
552
553    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
554    table.add_column("Pin")
555    table.add_column("Config")
556    table.add_column("I")
557    table.add_column("O")
558    table.add_column("AF", justify="right")
559    if pinout is not None:
560        table.add_column("Name")
561        table.add_column("Function")
562    for row in rows:
563        table.add_row(*row)
564    return table
class Device(emdbg.debug.px4.base.Base):
 17class Device(Base):
 18    """
 19    Accessors for the state of ARM Cortex-M CPU, STM32 identifiers, uptime, and
 20    NuttX kernel internals.
 21    """
 22    _HRT_CNT = 0x4001_0424
 23    _SCS_ICTR = 0xE000_E004
 24    _SCB_CPUID = 0xE000_ED00
 25    _SCB_VTOR = 0xE000_ED08
 26    _SCS_SHPR = 0xE000_ED18
 27    _NVIC_ISER = 0xE000_E100
 28    _NVIC_ISPR = 0xE000_E200
 29    _NVIC_IABR = 0xE000_E300
 30    _NVIC_IPR = 0xE000_E400
 31
 32    # Try them all until one of them does not return zero
 33    _DBG_IDCODE = [0xE004_2000, 0x5C00_1000]
 34
 35    @cached_property
 36    def _IDCODE_REVISION(self):
 37        return {
 38            0x1000: "A",
 39            0x1001: "Z",
 40            0x1003: "Y",
 41            0x1007: "4",
 42            0x2001: "X",
 43            0x2003: "Y",
 44        }.get(self.rev, "")
 45
 46    @cached_property
 47    def _IDCODE_DEVICE(self):
 48        return {
 49            0x0415: "STM32L47/L48xx",
 50            0x0451: "STM32F76xx, STM32F77xx",
 51            0x0450: "STM32H742, STM32H743/753, STM32H750",
 52            0x0483: "STM32H723/733, STM32H725/735, STM32H730",
 53        }.get(self.devid, "Unknown")
 54
 55    @cached_property
 56    def _GPIOS(self):
 57        return {
 58            0x0415: list(range(0x4800_0000, 0x4800_2000, 0x400)),
 59            # FMUv5x/v6x don't use ports J and K
 60            0x0451: list(range(0x4002_0000, 0x4002_2001, 0x400)),
 61            0x0450: list(range(0x5802_0000, 0x5802_2001, 0x400)),
 62            0x0483: list(range(0x5802_0000, 0x5802_2C01, 0x400)),
 63        }.get(self.devid, [])
 64
 65    @cached_property
 66    def _SYSTEM_MEMORIES(self):
 67        mems = [(0xE000_0000, 0x10_0000)]
 68        mems += {
 69            0x0415: [(0x1FFF_7500, 0x100)],
 70            0x0451: [(0x1FF0_F420, 0x100), (0x1FFF_7B00, 0x100)],
 71            **dict.fromkeys([0x0450, 0x0483],
 72                    [(0x1FF1_E800, 0x100), (0x58000524, 4)])
 73        }.get(self.devid, [])
 74        return mems
 75
 76    @cached_property
 77    def _PERIPHERALS(self):
 78        if self._SVD_FILE is None: return []
 79        from cmsis_svd.parser import SVDParser
 80        device = SVDParser.for_xml_file(self._SVD_FILE).get_device()
 81        registers = [(per.base_address + r.address_offset,
 82                      per.base_address + r.address_offset + r.size//8)
 83                     for per in device.peripherals for r in per.registers]
 84        registers.sort()
 85        ranges = []
 86        cluster = 512
 87        current = registers[0]
 88        for (regl, regh) in registers[1:]:
 89            if (current[1] + cluster) > regh:
 90                current = (current[0], regh)
 91            else:
 92                ranges.append(current)
 93                current = (regl, regh)
 94        ranges.append(current)
 95        return [(r[0], r[1] - r[0]) for r in ranges]
 96
 97    @cached_property
 98    def _MEMORIES(self):
 99        mems = {
100            0x0415: [
101                (0x1000_0000, 0x20000), # SRAM2
102                (0x2000_0000, 0x20000), # SRAM1
103            ],
104            0x0451: [
105                # (0x0000_0000, 0x04000), # ITCM
106                (0x2000_0000, 0x80000), # DTCM, SRAM1, SRAM2
107            ],
108            **dict.fromkeys([0x0450, 0x0483], [
109                # (0x0000_0000, 0x10000), # ITCM
110                (0x2000_0000, 0x20000), # DTCM
111                (0x2400_0000, 0x80000), # AXI_SRAM
112                (0x3000_0000, 0x48000), # SRAM1, SRAM2, SRAM3
113                (0x3800_0000, 0x10000), # SRAM4
114                (0x3880_0000, 0x01000), # Backup SRAM
115                (0x5C00_1000, 4),       # IDCODE
116            ]),
117        }.get(self.devid, [])
118        mems += self._PERIPHERALS
119        mems += self._SYSTEM_MEMORIES
120        return sorted(mems)
121
122    @cached_property
123    def _SVD_FILE(self):
124        return {
125            # 0x0415: Path(__file__).parents[1] / "data/STM32L4x6.svd",
126            0x0451: Path(__file__).parents[1] / "data/STM32F765.svd",
127            0x0450: Path(__file__).parents[1] / "data/STM32H753.svd",
128            # 0x0483: Path(__file__).parents[1] / "data/STM32H7x3.svd",
129        }.get(self.devid)
130
131    @dataclass
132    class Gpio:
133        port: str
134        index: int
135        moder: int
136        otyper: int
137        speedr: int
138        pupdr: int
139        idr: int
140        odr: int
141        lockr: int
142        afr: int
143
144    @dataclass
145    class Irq:
146        index: int
147        """Index of the IRQ starting at zero"""
148        handler: "gdb.Block"
149        """Function handler of the IRQ"""
150        priority: int
151        """Priority of the IRQ"""
152        is_enabled: bool
153        """Is interrupt enabled"""
154        is_pending: bool
155        """Is interrupt pending"""
156        is_active: bool
157        """Is interrupt active"""
158
159    @dataclass
160    class IrqNuttX(Irq):
161        arg: "gdb.Value"
162        """Optional argument passed to the IRQ handler"""
163
164    def __init__(self, gdb):
165        super().__init__(gdb)
166        self.architecture = self._arch.name()
167        self._hrt_counter = self.addr_ptr(self._HRT_CNT, "uint16_t")
168
169    @cached_property
170    def _hrt_base(self):
171        return self.lookup_static_symbol_in_function_ptr("base_time", "hrt_absolute_time")
172
173    def _read_bits(self, base, index, size):
174        shift = ((index * size) % 64)
175        offset = (index * size) // 64
176        mask = ((1 << size) - 1) << shift
177        bits = self.read_memory(base + offset, 8).cast("Q")[0]
178        return (bits & mask) >> shift
179
180    def _priority(self, index):
181        if index == -15: return -3
182        if index == -14: return -2
183        if index == -13: return -1
184        if index < 0: return self._read_bits(self._SCS_SHPR, index + 16, 8)
185        return self._read_bits(self._NVIC_IPR, index, 8)
186
187    def _enabled(self, index):
188        # if index < 0: return self._read_bits1(self._SCS_, index);
189        return self._read_bits(self._NVIC_ISER, index, 1)
190
191    def _pending(self, index):
192        return self._read_bits(self._NVIC_ISPR, index, 1)
193
194    def _active(self, index):
195        return self._read_bits(self._NVIC_IABR, index, 1)
196
197    @cached_property
198    def uptime(self) -> int:
199        """The uptime in microseconds as read from the NuttX high-resolution timer (HRT)"""
200        if self._hrt_base is None: return 0
201        return int(self._hrt_base.dereference() + self._hrt_counter.dereference())
202
203    @cached_property
204    def max_interrupts(self) -> int:
205        """Maximum number of interrupts implemented on this device"""
206        return 32 * (self.read_uint(self._SCS_ICTR, 4) + 1)
207
208    @cached_property
209    def vector_table(self) -> list[Irq]:
210        """The vector table as stored inside the SCB->VTOR"""
211        # SCS = 0xE000E000, SCB = 0xE000ED00, SCB->VTOR = 0xE000ED08
212        # TODO: Cortex-M0 has no VTOR, Cortex-M0+ has one if implemented
213        vtor = self._gdb.Value(self._SCB_VTOR).cast(self.uint32.pointer())
214        vtor = vtor.dereference().cast(self.uint32.pointer())
215        entries = []
216        for ii in range(self.max_interrupts):
217            ii -= 16
218            entries.append(self.Irq(ii, self.block(vtor[ii+16]), self._priority(ii),
219                                    self._enabled(ii), self._pending(ii), self._active(ii)))
220        return entries
221
222    @cached_property
223    def vector_table_nuttx(self) -> dict[int, IrqNuttX]:
224        """
225        The index, handler and argument of the NuttX interrupt table if the
226        handler is not empty and is not `irq_unexpected_isr`.
227        """
228        g_irqvector = self._gdb.lookup_global_symbol("g_irqvector")
229        vectors = {}
230        for ii, vector in enumerate(utils.gdb_iter(g_irqvector)):
231            if handler := vector["handler"]:
232                block = self.block(handler)
233                if block.function and block.function.name == "irq_unexpected_isr":
234                    continue
235                ii -= 16
236                vectors[ii] = self.IrqNuttX(ii, block, self._priority(ii),
237                                            self._enabled(ii), self._pending(ii),
238                                            self._active(ii), vector["arg"])
239        return vectors
240
241    @property
242    def gpios(self) -> list[Gpio]:
243        """List of GPIOs as read from the device."""
244        result = []
245        for jj, gper_addr in enumerate(self._GPIOS):
246            port = chr(ord("A") + jj)
247            gper = self.read_memory(gper_addr, 0x28).cast("I")
248            for ii in range(16):
249                _1v = lambda index: (gper[index] >> ii) & 0x1
250                _2v = lambda index: (gper[index] >> ii*2) & 0x3
251                moder, speedr, pupdr = _2v(0), _2v(2), _2v(3)
252                otyper, idr, odr, lockr = _1v(1), _1v(4), _1v(5), _1v(7)
253                afr = ((gper[9] << 32 | gper[8]) >> ii*4) & 0xf
254                g = self.Gpio(port, ii, moder, otyper, speedr, pupdr, idr, odr, lockr, afr)
255                result.append(g)
256        return result
257
258    def coredump(self, memories: list[tuple[int, int]] = None, with_flash: bool = False) -> tuple[str, int]:
259        """
260        Reads the memories and registers and returns them as a formatted string
261        that is compatible with CrashDebug (see `emdbg.debug.crashdebug`).
262
263        :param memories: list of memory ranges (start, size) to dump
264        :param with_flash: also dump the entire non-volatile storage
265        :return: coredump formatted as string and coredump size
266        """
267        if memories is None:
268            memories = self._MEMORIES
269        if with_flash and self.flash_size:
270            memories += [(0x0800_0000, self.flash_size)]
271        lines = []
272        total_size = 0
273        for addr, size in memories:
274            try:
275                data = self.read_memory(addr, size).cast("I")
276                total_size += size
277            except Exception as e:
278                print(f"Failed to read whole range [{addr:#x}, {addr+size:#x}]! {e}")
279                data = []
280                for offset in range(0, size, 4):
281                    try:
282                        data.append(self.read_memory(addr + offset, 4).cast("I")[0])
283                        total_size += 4
284                    except Exception as e:
285                        print(f"Failed to read uint32_t {addr+offset:#x}! {e}")
286                        data.append(0)
287                        continue
288            for ii, values in enumerate(utils.chunks(data, 4, 0)):
289                values = (hex(v & 0xffffffff) for v in values)
290                lines.append(f"{hex(addr + ii * 16)}: {' '.join(values)}")
291
292        for name, value in self.registers.items():
293            if re.match(r"d\d+", name):
294                lines.append(f"{name:<28} {float(value):<28} (raw {value & 0xffffffffffffffff:#x})")
295            elif re.match(r"s\d+", name):
296                lines.append(f"{name:<28} {float(value):<28} (raw {value & 0xffffffff:#x})")
297            else:
298                lines.append(f"{name:<28} {hex(value & 0xffffffff):<28} {int(value)}")
299
300        return "\n".join(lines), total_size
301
302    @cached_property
303    def cpuid(self) -> int:
304        """The SCB->CPUID value"""
305        return self.read_uint(self._SCB_CPUID, 4)
306
307    @cached_property
308    def idcode(self) -> int:
309        """The STM32-specific DBG->IDCODE value"""
310        for addr in self._DBG_IDCODE:
311            if idcode := (self.read_uint(addr, 4) & 0xffff0fff):
312                return idcode
313        return 0
314
315    @cached_property
316    def flash_size(self) -> int:
317        """The FLASH size in bytes"""
318        addr = {
319            0x0415: 0x1FFF_75E0,
320            0x0451: 0x1FF0_F442,
321            0x0450: 0x1FF1_E880,
322            0x0483: 0x1FF1_E880,
323        }.get(self.devid)
324        if addr is None: return 0
325        return self.read_uint(addr, 2) * 1024
326
327    @cached_property
328    def line(self) -> str:
329        """The device family and name"""
330        if self.devid == 0x0483:
331            return self.read_string(0x1FF1_E8C0, length=4)[::-1]
332        return self._IDCODE_DEVICE
333
334    @cached_property
335    def uid(self) -> int:
336        """The device's unique identifier as a big integer"""
337        addr = {
338            0x0415: 0x1FFF_7590,
339            0x0451: 0x1FF0_F420,
340            0x0450: 0x1FF1_E800,
341            0x0483: 0x1FF1_E800,
342        }.get(self.devid)
343        if addr is None: return 0
344        return int.from_bytes(self.read_memory(addr, 3*4).tobytes(), "little")
345
346    @cached_property
347    def package(self) -> str:
348        """The device package"""
349
350        if self.devid == 0x0415:
351            return {
352                0b00000: "LQFP64",
353                0b00010: "LQFP100",
354                0b00011: "UFBGA132",
355                0b00100: "LQFP144, UFBGA144, WLCSP72, WLCSP81 or WLCSP86",
356                0b10000: "UFBGA169, WLCSP115",
357                0b10001: "WLCSP100",
358            }.get(self.read_uint(0x1FFF_7500, 1) & 0x1f, "Reserved")
359        if self.devid == 0x0451:
360            return {
361                0b111: "LQFP208 or TFBGA216",
362                0b110: "LQFP208 or TFBGA216",
363                0b101: "LQFP176",
364                0b100: "LQFP176",
365                0b011: "WLCSP180",
366                0b010: "LQFP144 ",
367                0b001: "LQFP100",
368            }.get(self.read_uint(0x1FFF_7BF1, 1) & 0x7, "Reserved")
369        if self.devid == 0x0450:
370            return {
371                0b0000: "LQFP100",
372                0b0010: "TQFP144",
373                0b0101: "TQFP176/UFBGA176",
374                0b1000: "LQFP208/TFBGA240",
375            }.get(self.read_uint(0x58000524, 1) & 0xf, "All pads enabled")
376        if self.devid == 0x0483:
377            return {
378                0b0000: "VFQFPN68 Industrial",
379                0b0001: "LQFP100 Legacy / TFBGA100 Legacy",
380                0b0010: "LQFP100 Industrial",
381                0b0011: "TFBGA100 Industrial",
382                0b0100: "WLCSP115 Industrial",
383                0b0101: "LQFP144 Legacy",
384                0b0110: "UFBGA144 Legacy",
385                0b0111: "LQFP144 Industrial",
386                0b1000: "UFBGA169 Industrial",
387                0b1001: "UFBGA176+25 Industrial",
388                0b1010: "LQFP176 Industrial",
389            }.get(self.read_uint(0x58000524, 1) & 0xf, "All pads enabled")
390        return "?"
391
392    @cached_property
393    def devid(self) -> int:
394        """The STM32-specific device id part of DBG->IDCODE"""
395        return self.idcode & 0xfff
396
397    @cached_property
398    def rev(self) -> int:
399        """The STM32-specific revision part of DBG->IDCODE"""
400        return self.idcode >> 16

Accessors for the state of ARM Cortex-M CPU, STM32 identifiers, uptime, and NuttX kernel internals.

Device(gdb)
164    def __init__(self, gdb):
165        super().__init__(gdb)
166        self.architecture = self._arch.name()
167        self._hrt_counter = self.addr_ptr(self._HRT_CNT, "uint16_t")
architecture
uptime: int
197    @cached_property
198    def uptime(self) -> int:
199        """The uptime in microseconds as read from the NuttX high-resolution timer (HRT)"""
200        if self._hrt_base is None: return 0
201        return int(self._hrt_base.dereference() + self._hrt_counter.dereference())

The uptime in microseconds as read from the NuttX high-resolution timer (HRT)

max_interrupts: int
203    @cached_property
204    def max_interrupts(self) -> int:
205        """Maximum number of interrupts implemented on this device"""
206        return 32 * (self.read_uint(self._SCS_ICTR, 4) + 1)

Maximum number of interrupts implemented on this device

vector_table: list[Device.Irq]
208    @cached_property
209    def vector_table(self) -> list[Irq]:
210        """The vector table as stored inside the SCB->VTOR"""
211        # SCS = 0xE000E000, SCB = 0xE000ED00, SCB->VTOR = 0xE000ED08
212        # TODO: Cortex-M0 has no VTOR, Cortex-M0+ has one if implemented
213        vtor = self._gdb.Value(self._SCB_VTOR).cast(self.uint32.pointer())
214        vtor = vtor.dereference().cast(self.uint32.pointer())
215        entries = []
216        for ii in range(self.max_interrupts):
217            ii -= 16
218            entries.append(self.Irq(ii, self.block(vtor[ii+16]), self._priority(ii),
219                                    self._enabled(ii), self._pending(ii), self._active(ii)))
220        return entries

The vector table as stored inside the SCB->VTOR

vector_table_nuttx: dict[int, Device.IrqNuttX]
222    @cached_property
223    def vector_table_nuttx(self) -> dict[int, IrqNuttX]:
224        """
225        The index, handler and argument of the NuttX interrupt table if the
226        handler is not empty and is not `irq_unexpected_isr`.
227        """
228        g_irqvector = self._gdb.lookup_global_symbol("g_irqvector")
229        vectors = {}
230        for ii, vector in enumerate(utils.gdb_iter(g_irqvector)):
231            if handler := vector["handler"]:
232                block = self.block(handler)
233                if block.function and block.function.name == "irq_unexpected_isr":
234                    continue
235                ii -= 16
236                vectors[ii] = self.IrqNuttX(ii, block, self._priority(ii),
237                                            self._enabled(ii), self._pending(ii),
238                                            self._active(ii), vector["arg"])
239        return vectors

The index, handler and argument of the NuttX interrupt table if the handler is not empty and is not irq_unexpected_isr.

gpios: list[Device.Gpio]
241    @property
242    def gpios(self) -> list[Gpio]:
243        """List of GPIOs as read from the device."""
244        result = []
245        for jj, gper_addr in enumerate(self._GPIOS):
246            port = chr(ord("A") + jj)
247            gper = self.read_memory(gper_addr, 0x28).cast("I")
248            for ii in range(16):
249                _1v = lambda index: (gper[index] >> ii) & 0x1
250                _2v = lambda index: (gper[index] >> ii*2) & 0x3
251                moder, speedr, pupdr = _2v(0), _2v(2), _2v(3)
252                otyper, idr, odr, lockr = _1v(1), _1v(4), _1v(5), _1v(7)
253                afr = ((gper[9] << 32 | gper[8]) >> ii*4) & 0xf
254                g = self.Gpio(port, ii, moder, otyper, speedr, pupdr, idr, odr, lockr, afr)
255                result.append(g)
256        return result

List of GPIOs as read from the device.

def coredump( self, memories: list[tuple[int, int]] = None, with_flash: bool = False) -> tuple[str, int]:
258    def coredump(self, memories: list[tuple[int, int]] = None, with_flash: bool = False) -> tuple[str, int]:
259        """
260        Reads the memories and registers and returns them as a formatted string
261        that is compatible with CrashDebug (see `emdbg.debug.crashdebug`).
262
263        :param memories: list of memory ranges (start, size) to dump
264        :param with_flash: also dump the entire non-volatile storage
265        :return: coredump formatted as string and coredump size
266        """
267        if memories is None:
268            memories = self._MEMORIES
269        if with_flash and self.flash_size:
270            memories += [(0x0800_0000, self.flash_size)]
271        lines = []
272        total_size = 0
273        for addr, size in memories:
274            try:
275                data = self.read_memory(addr, size).cast("I")
276                total_size += size
277            except Exception as e:
278                print(f"Failed to read whole range [{addr:#x}, {addr+size:#x}]! {e}")
279                data = []
280                for offset in range(0, size, 4):
281                    try:
282                        data.append(self.read_memory(addr + offset, 4).cast("I")[0])
283                        total_size += 4
284                    except Exception as e:
285                        print(f"Failed to read uint32_t {addr+offset:#x}! {e}")
286                        data.append(0)
287                        continue
288            for ii, values in enumerate(utils.chunks(data, 4, 0)):
289                values = (hex(v & 0xffffffff) for v in values)
290                lines.append(f"{hex(addr + ii * 16)}: {' '.join(values)}")
291
292        for name, value in self.registers.items():
293            if re.match(r"d\d+", name):
294                lines.append(f"{name:<28} {float(value):<28} (raw {value & 0xffffffffffffffff:#x})")
295            elif re.match(r"s\d+", name):
296                lines.append(f"{name:<28} {float(value):<28} (raw {value & 0xffffffff:#x})")
297            else:
298                lines.append(f"{name:<28} {hex(value & 0xffffffff):<28} {int(value)}")
299
300        return "\n".join(lines), total_size

Reads the memories and registers and returns them as a formatted string that is compatible with CrashDebug (see emdbg.debug.crashdebug).

Parameters
  • memories: list of memory ranges (start, size) to dump
  • with_flash: also dump the entire non-volatile storage
Returns

coredump formatted as string and coredump size

cpuid: int
302    @cached_property
303    def cpuid(self) -> int:
304        """The SCB->CPUID value"""
305        return self.read_uint(self._SCB_CPUID, 4)

The SCB->CPUID value

idcode: int
307    @cached_property
308    def idcode(self) -> int:
309        """The STM32-specific DBG->IDCODE value"""
310        for addr in self._DBG_IDCODE:
311            if idcode := (self.read_uint(addr, 4) & 0xffff0fff):
312                return idcode
313        return 0

The STM32-specific DBG->IDCODE value

flash_size: int
315    @cached_property
316    def flash_size(self) -> int:
317        """The FLASH size in bytes"""
318        addr = {
319            0x0415: 0x1FFF_75E0,
320            0x0451: 0x1FF0_F442,
321            0x0450: 0x1FF1_E880,
322            0x0483: 0x1FF1_E880,
323        }.get(self.devid)
324        if addr is None: return 0
325        return self.read_uint(addr, 2) * 1024

The FLASH size in bytes

line: str
327    @cached_property
328    def line(self) -> str:
329        """The device family and name"""
330        if self.devid == 0x0483:
331            return self.read_string(0x1FF1_E8C0, length=4)[::-1]
332        return self._IDCODE_DEVICE

The device family and name

uid: int
334    @cached_property
335    def uid(self) -> int:
336        """The device's unique identifier as a big integer"""
337        addr = {
338            0x0415: 0x1FFF_7590,
339            0x0451: 0x1FF0_F420,
340            0x0450: 0x1FF1_E800,
341            0x0483: 0x1FF1_E800,
342        }.get(self.devid)
343        if addr is None: return 0
344        return int.from_bytes(self.read_memory(addr, 3*4).tobytes(), "little")

The device's unique identifier as a big integer

package: str
346    @cached_property
347    def package(self) -> str:
348        """The device package"""
349
350        if self.devid == 0x0415:
351            return {
352                0b00000: "LQFP64",
353                0b00010: "LQFP100",
354                0b00011: "UFBGA132",
355                0b00100: "LQFP144, UFBGA144, WLCSP72, WLCSP81 or WLCSP86",
356                0b10000: "UFBGA169, WLCSP115",
357                0b10001: "WLCSP100",
358            }.get(self.read_uint(0x1FFF_7500, 1) & 0x1f, "Reserved")
359        if self.devid == 0x0451:
360            return {
361                0b111: "LQFP208 or TFBGA216",
362                0b110: "LQFP208 or TFBGA216",
363                0b101: "LQFP176",
364                0b100: "LQFP176",
365                0b011: "WLCSP180",
366                0b010: "LQFP144 ",
367                0b001: "LQFP100",
368            }.get(self.read_uint(0x1FFF_7BF1, 1) & 0x7, "Reserved")
369        if self.devid == 0x0450:
370            return {
371                0b0000: "LQFP100",
372                0b0010: "TQFP144",
373                0b0101: "TQFP176/UFBGA176",
374                0b1000: "LQFP208/TFBGA240",
375            }.get(self.read_uint(0x58000524, 1) & 0xf, "All pads enabled")
376        if self.devid == 0x0483:
377            return {
378                0b0000: "VFQFPN68 Industrial",
379                0b0001: "LQFP100 Legacy / TFBGA100 Legacy",
380                0b0010: "LQFP100 Industrial",
381                0b0011: "TFBGA100 Industrial",
382                0b0100: "WLCSP115 Industrial",
383                0b0101: "LQFP144 Legacy",
384                0b0110: "UFBGA144 Legacy",
385                0b0111: "LQFP144 Industrial",
386                0b1000: "UFBGA169 Industrial",
387                0b1001: "UFBGA176+25 Industrial",
388                0b1010: "LQFP176 Industrial",
389            }.get(self.read_uint(0x58000524, 1) & 0xf, "All pads enabled")
390        return "?"

The device package

devid: int
392    @cached_property
393    def devid(self) -> int:
394        """The STM32-specific device id part of DBG->IDCODE"""
395        return self.idcode & 0xfff

The STM32-specific device id part of DBG->IDCODE

rev: int
397    @cached_property
398    def rev(self) -> int:
399        """The STM32-specific revision part of DBG->IDCODE"""
400        return self.idcode >> 16

The STM32-specific revision part of DBG->IDCODE

@dataclass
class Device.Gpio:
131    @dataclass
132    class Gpio:
133        port: str
134        index: int
135        moder: int
136        otyper: int
137        speedr: int
138        pupdr: int
139        idr: int
140        odr: int
141        lockr: int
142        afr: int
Device.Gpio( port: str, index: int, moder: int, otyper: int, speedr: int, pupdr: int, idr: int, odr: int, lockr: int, afr: int)
port: str
index: int
moder: int
otyper: int
speedr: int
pupdr: int
idr: int
odr: int
lockr: int
afr: int
@dataclass
class Device.Irq:
144    @dataclass
145    class Irq:
146        index: int
147        """Index of the IRQ starting at zero"""
148        handler: "gdb.Block"
149        """Function handler of the IRQ"""
150        priority: int
151        """Priority of the IRQ"""
152        is_enabled: bool
153        """Is interrupt enabled"""
154        is_pending: bool
155        """Is interrupt pending"""
156        is_active: bool
157        """Is interrupt active"""
Device.Irq( index: int, handler: "'gdb.Block'", priority: int, is_enabled: bool, is_pending: bool, is_active: bool)
index: int

Index of the IRQ starting at zero

handler: "'gdb.Block'"

Function handler of the IRQ

priority: int

Priority of the IRQ

is_enabled: bool

Is interrupt enabled

is_pending: bool

Is interrupt pending

is_active: bool

Is interrupt active

@dataclass
class Device.IrqNuttX(Device.Irq):
159    @dataclass
160    class IrqNuttX(Irq):
161        arg: "gdb.Value"
162        """Optional argument passed to the IRQ handler"""
Device.IrqNuttX( index: int, handler: "'gdb.Block'", priority: int, is_enabled: bool, is_pending: bool, is_active: bool, arg: "'gdb.Value'")
arg: "'gdb.Value'"

Optional argument passed to the IRQ handler

def discover(gdb) -> rich.table.Table:
403def discover(gdb) -> Table:
404    """
405    Reads the device identifier registers and outputs a human readable string if possible.
406    :return: description string
407    """
408    dev = Device(gdb)
409    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
410    table.add_column("Device")
411    table.add_column("Revision")
412    table.add_column("Flash")
413    table.add_column("Package")
414    table.add_column("UID")
415    table.add_row(f"{dev.devid:#4x}: {dev.line}",
416                  f"{dev.rev:#4x}: rev {dev._IDCODE_REVISION}",
417                  f"{dev.flash_size//1024}kB", dev.package,
418                  f"{dev.uid:x}")
419    return table

Reads the device identifier registers and outputs a human readable string if possible.

Returns

description string

def all_registers(gdb) -> dict[str, int]:
422def all_registers(gdb) -> dict[str, int]:
423    """Return a dictionary of register name and values"""
424    return Device(gdb).registers

Return a dictionary of register name and values

def all_registers_as_table(gdb, columns: int = 3) -> rich.table.Table:
427def all_registers_as_table(gdb, columns: int = 3) -> Table:
428    """
429    Format the Cortex-M CPU+FPU registers and their values into a simple table.
430
431    :param columns: The number of columns to spread the registers across.
432    """
433    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
434    table.add_column("Name")
435    table.add_column("Hexadecimal", justify="right")
436    table.add_column("Decimal", justify="right")
437    table.add_column("Binary", justify="right")
438    for reg, value in all_registers(gdb).items():
439        table.add_row(reg, f"{value:x}", str(value), f"{value:b}")
440    return table

Format the Cortex-M CPU+FPU registers and their values into a simple table.

Parameters
  • columns: The number of columns to spread the registers across.
def vector_table(gdb) -> dict[int, Device.IrqNuttX]:
443def vector_table(gdb) -> dict[int, Device.IrqNuttX]:
444    """Return a dictionary of NuttX interrupt numbers and their handlers with arguments"""
445    return Device(gdb).vector_table_nuttx

Return a dictionary of NuttX interrupt numbers and their handlers with arguments

def vector_table_as_table(gdb, columns: int = 1) -> rich.table.Table:
448def vector_table_as_table(gdb, columns: int = 1) -> Table:
449    """
450    Format the NuttX interrupts and their handlers with arguments into a simple table.
451
452    :param columns: The number of columns to spread the interrupts across.
453    """
454    def _fname(block):
455        count = 0
456        while block and block.function is None:
457            block = block.superblock
458            count += 1
459        if block.function:
460            return f"{block.function.name} {'^' * count}"
461        return f"{block} ?"
462
463    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
464    table.add_column("IRQ", justify="right")
465    table.add_column("EPA")
466    table.add_column("Prio")
467    table.add_column("Address")
468    table.add_column("Function")
469    table.add_column("Argument")
470    for idx, irq in vector_table(gdb).items():
471        table.add_row(str(idx),
472                      ("e" if irq.is_enabled else " ") +
473                      ("p" if irq.is_pending else " ") +
474                      ("a" if irq.is_active else " "),
475                      f"{irq.priority:x}", hex(irq.handler.start),
476                      _fname(irq.handler), str(irq.arg) or "",
477                      style="bold blue" if irq.is_active else None)
478    return table

Format the NuttX interrupts and their handlers with arguments into a simple table.

Parameters
  • columns: The number of columns to spread the interrupts across.
def coredump( gdb, memories: list[tuple[int, int]] = None, with_flash: bool = False, filename: pathlib.Path = None):
481def coredump(gdb, memories: list[tuple[int, int]] = None,
482             with_flash: bool = False, filename: Path = None):
483    """
484    Dumps the memories and register state into a file.
485
486    :param memories: List of (addr, size) tuples that describe which memories to dump.
487    :param with_flash: Also dump the entire non-volatile storage.
488    :param filename: Target filename, or `coredump_{datetime}.txt` by default.
489    """
490    if filename is None:
491        filename = utils.add_datetime("coredump.txt")
492    print("Starting coredump...", flush=True)
493    start = time.perf_counter()
494    output, size = Device(gdb).coredump(memories, with_flash)
495    Path(filename).write_text(output)
496    end = time.perf_counter()
497    print(f"Dumped {size//1000}kB in {(end - start):.1f}s ({int(size/((end - start)*1000))}kB/s)")

Dumps the memories and register state into a file.

Parameters
  • memories: List of (addr, size) tuples that describe which memories to dump.
  • with_flash: Also dump the entire non-volatile storage.
  • filename: Target filename, or coredump_{datetime}.txt by default.
def all_gpios_as_table( gdb, pinout: dict[str, tuple[str, str]] = None, fn_filter=None, sort_by=None, columns: int = 2) -> rich.table.Table:
500def all_gpios_as_table(gdb, pinout: dict[str, tuple[str, str]] = None,
501                       fn_filter = None, sort_by = None, columns: int = 2) -> Table:
502    """
503    Reads the GPIO peripheral space and prints a table of the individual pin
504    configuration, input/output state and alternate function. If a pinout is
505    provided, the pins will be matched with their names and functions.
506
507    Config: Condensed view with omitted defaults.
508        MODER:  IN=Input, OUT=Output, ALT=Alternate Function, AN=Analog,
509        OTYPER: +OD=OpenDrain, (+PP=PushPull omitted),
510        PUPDR:  +PU=PullUp, +PD=PullDown, (+FL=Floating omitted),
511        SPEEDR: +M=Medium, +H=High, +VH=Very High, (+L=Low omitted).
512
513    Input (IDR), Output (ODR): _=Low, ^=High
514        Input only shown for IN, OUT, and ALT.
515        Output only shown for OUT.
516
517    Alternate Function (AFR): only shown when config is ALT.
518        Consult the datasheet for device-specific mapping.
519
520    :param pinout: A map of port+index -> (name, function).
521    :param pin_filter: A filter function that gets passed the entire row as a
522                       list and returns `True` if row is accepted.
523    :param sort_by: The name of the column to sort by: default is `PIN`.
524    :param columns: The number of columns to spread the GPIO table across.
525    """
526    rows = []
527    for gpio in Device(gdb).gpios:
528        name = f"{gpio.port}{gpio.index}"
529        if pinout is not None:
530             list(pinout.get(name, [""]*2))
531        config = "".join([["IN", "OUT", "ALT", "AN"][gpio.moder],
532                          ["", "+OD"][gpio.otyper],
533                          ["", "+PU", "+PD", "+!!"][gpio.pupdr],
534                          ["", "+M", "+H", "+VH"][gpio.speedr],
535                          ["", "+L"][gpio.lockr]])
536        idr = "" if gpio.moder == 3 else ["_", "^"][gpio.idr]
537        odr = ["_", "^"][gpio.odr] if gpio.moder == 1 else ""
538        afr = str(gpio.afr) if gpio.moder == 2 else ""
539        row = [name, config, idr, odr, afr]
540        if pinout is not None:
541            row += list(pinout.get(name, [""]*2))
542        if fn_filter is None or fn_filter(row):
543            rows.append(row)
544    if sort_by is not None:
545        def _sort(row):
546            pinf = ord(row[0][0]) * 100 + int(row[0][1:])
547            if sort_by == 0: return pinf
548            if sort_by == 4: return -1 if row[4] == "" else row[4]
549            if sort_by == 5: return (row[5], row[6], pinf)
550            if sort_by == 6: return (row[6], row[5], pinf)
551            return row[sort_by]
552        rows.sort(key=_sort)
553
554    table = Table(box=rich.box.MINIMAL_DOUBLE_HEAD)
555    table.add_column("Pin")
556    table.add_column("Config")
557    table.add_column("I")
558    table.add_column("O")
559    table.add_column("AF", justify="right")
560    if pinout is not None:
561        table.add_column("Name")
562        table.add_column("Function")
563    for row in rows:
564        table.add_row(*row)
565    return table

Reads the GPIO peripheral space and prints a table of the individual pin configuration, input/output state and alternate function. If a pinout is provided, the pins will be matched with their names and functions.

Config: Condensed view with omitted defaults. MODER: IN=Input, OUT=Output, ALT=Alternate Function, AN=Analog, OTYPER: +OD=OpenDrain, (+PP=PushPull omitted), PUPDR: +PU=PullUp, +PD=PullDown, (+FL=Floating omitted), SPEEDR: +M=Medium, +H=High, +VH=Very High, (+L=Low omitted).

Input (IDR), Output (ODR): _=Low, ^=High Input only shown for IN, OUT, and ALT. Output only shown for OUT.

Alternate Function (AFR): only shown when config is ALT. Consult the datasheet for device-specific mapping.

Parameters
  • pinout: A map of port+index -> (name, function).
  • pin_filter: A filter function that gets passed the entire row as a list and returns True if row is accepted.
  • sort_by: The name of the column to sort by: default is PIN.
  • columns: The number of columns to spread the GPIO table across.