|
| 1 | +#!/usr/bin/env python3 |
| 2 | +# Copyright 2025 Bertrik Sikken <bertrik@sikken.nl> |
| 3 | +import math |
| 4 | +import threading |
| 5 | +from enum import Enum |
| 6 | + |
| 7 | +import rclpy |
| 8 | +import serial |
| 9 | +from rclpy.node import Node |
| 10 | +from sensor_msgs.msg import LaserScan |
| 11 | +from std_msgs.msg import Header |
| 12 | + |
| 13 | + |
| 14 | +class FrameExtractor: |
| 15 | + class State(Enum): |
| 16 | + HEADER_1 = 1 |
| 17 | + HEADER_2 = 2 |
| 18 | + COLLECT = 3 |
| 19 | + |
| 20 | + def __init__(self) -> None: |
| 21 | + self.state = self.State.HEADER_1 |
| 22 | + self.index = 0 |
| 23 | + self.length = 0 |
| 24 | + self.data = bytearray(60) |
| 25 | + |
| 26 | + def __add_data(self, b): |
| 27 | + self.data[self.index] = b |
| 28 | + self.index += 1 |
| 29 | + |
| 30 | + def process(self, b) -> bytes | None: |
| 31 | + """ processes one byte, returns True if a full frame was received """ |
| 32 | + match self.state: |
| 33 | + case self.State.HEADER_1: |
| 34 | + self.index = 0 |
| 35 | + if b == 0x55: |
| 36 | + self.__add_data(b) |
| 37 | + self.state = self.State.HEADER_2 |
| 38 | + |
| 39 | + case self.State.HEADER_2: |
| 40 | + if b == 0xAA: |
| 41 | + self.__add_data(b) |
| 42 | + self.length = len(self.data) |
| 43 | + self.state = self.State.COLLECT |
| 44 | + else: |
| 45 | + self.state = self.State.HEADER_1 |
| 46 | + self.process(b) |
| 47 | + |
| 48 | + case self.State.COLLECT: |
| 49 | + if self.index < self.length: |
| 50 | + self.__add_data(b) |
| 51 | + if self.index == self.length: |
| 52 | + # done |
| 53 | + self.state = self.State.HEADER_1 |
| 54 | + return self.data |
| 55 | + return None |
| 56 | + |
| 57 | + |
| 58 | +class MysteryLidar: |
| 59 | + def __init__(self, device): |
| 60 | + self.serial = serial.Serial(device, baudrate=230400, timeout=0.1) |
| 61 | + self.extractor = FrameExtractor() |
| 62 | + |
| 63 | + def open(self) -> None: |
| 64 | + if not self.serial.is_open: |
| 65 | + self.serial.open() |
| 66 | + |
| 67 | + def poll(self) -> bytes | None: |
| 68 | + num = self.serial.in_waiting |
| 69 | + while num > 0: |
| 70 | + num -= 1 |
| 71 | + b = self.serial.read()[0] |
| 72 | + result = self.extractor.process(b) |
| 73 | + if result: |
| 74 | + return result |
| 75 | + return None |
| 76 | + |
| 77 | + def close(self) -> None: |
| 78 | + self.serial.close() |
| 79 | + |
| 80 | + |
| 81 | +class LidarNode(Node): |
| 82 | + def __init__(self): |
| 83 | + super().__init__('lidar') |
| 84 | + self.declare_parameter('device', value='/dev/ttyUSB0') |
| 85 | + self.declare_parameter('topic', value='/scan') |
| 86 | + self.declare_parameter('frame_id', value='laser') |
| 87 | + |
| 88 | + device = self.get_parameter('device').get_parameter_value().string_value |
| 89 | + self.lidar = MysteryLidar(device) |
| 90 | + |
| 91 | + self.frame_id = self.get_parameter('frame_id').get_parameter_value().string_value |
| 92 | + |
| 93 | + topic = self.get_parameter('topic').get_parameter_value().string_value |
| 94 | + self.publisher = self.create_publisher(LaserScan, topic, 10) |
| 95 | + |
| 96 | + self.thread = threading.Thread(target=self.node_task()) |
| 97 | + self.thread.start() |
| 98 | + |
| 99 | + def node_task(self) -> None: |
| 100 | + self.lidar.open() |
| 101 | + while rclpy.ok(): |
| 102 | + frame = self.lidar.poll() |
| 103 | + if frame: |
| 104 | + self.publish_scan(frame) |
| 105 | + self.lidar.close() |
| 106 | + |
| 107 | + def publish_scan(self, frame: bytes) -> None: |
| 108 | + fsa = (frame[6] + (frame[7] << 8)) / 64.0 - 640 |
| 109 | + lsa = (frame[56] + (frame[57] << 8)) / 64.0 - 640 |
| 110 | + if lsa < fsa: |
| 111 | + lsa += 360 |
| 112 | + step = (lsa - fsa) / 16 |
| 113 | + |
| 114 | + header = Header(frame_id=self.frame_id, stamp=self.get_clock().now().to_msg()) |
| 115 | + msg = LaserScan(header=header) |
| 116 | + msg.angle_min = math.radians(fsa) |
| 117 | + msg.angle_max = math.radians(lsa) |
| 118 | + msg.angle_increment = math.radians(step) |
| 119 | + msg.range_min = 0.0 |
| 120 | + msg.range_max = float(0x3FFF) |
| 121 | + # time between full 360 sweep: approx 6 rotations per second |
| 122 | + msg.scan_time = 1.0 / 6 |
| 123 | + # time between rays: 6 fps, 36*16 rays per scan |
| 124 | + msg.time_increment = msg.scan_time * 10 / (360 * 16) |
| 125 | + |
| 126 | + idx = 8 |
| 127 | + for i in range(16): |
| 128 | + dist = (frame[idx] + (frame[idx + 1] << 8)) & 0x3FFF |
| 129 | + intensity = frame[idx + 2] |
| 130 | + idx += 3 |
| 131 | + msg.ranges.append(float(dist)) |
| 132 | + msg.intensities.append(float(intensity)) |
| 133 | + |
| 134 | + self.publisher.publish(msg) |
| 135 | + |
| 136 | + |
| 137 | +def main(args=None): |
| 138 | + # Set up a transformer using: |
| 139 | + # ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0 base_link laser |
| 140 | + # Visualize using rvis2, add a 'LaserScan' display and choose topic '/scan' and style 'Points' |
| 141 | + # |
| 142 | + rclpy.init(args=args) |
| 143 | + lidar_node = LidarNode() |
| 144 | + rclpy.spin(lidar_node) |
| 145 | + lidar_node.destroy_node() |
| 146 | + rclpy.shutdown() |
| 147 | + |
| 148 | + |
| 149 | +if __name__ == '__main__': |
| 150 | + main() |
0 commit comments