카테고리 없음

(파이썬/YDLidar G2) Frequency 설정 스크립트

미친토끼 2025. 3. 26. 18:15

YDLidar G2는 주파수(초당 회전수) 변경을 쉽게 할 수 있습니다. 회전이 빨라질수록 주위의 변화를 빠르게 감지하지만, 그만큼 각도 해상도가 듬성듬성해지니만큼 주의가 필요합니다.

G2에는 0.1Hz, 1Hz 단위로 주파수를 변경할 수 있는 명령어를 제공하는데요, 그것을 사용해서 간단히 파이썬 스크립트를 작성해보았습니다.

 

각각의 파일을 chmod 777해서, 어디 PATH 걸린 곳에 넣어놓고 쓰시면 되겠죠.

 

scan: 스캔 시작 명령. 회전하기 시작함.

#!/bin/python3

import serial

s = serial.Serial('/dev/ttyUSB0', 230400)
s.write(b'\xa5\x60')  # start scan

 

stop: 스캔 중지 명령. 회전을 멈춤.

#!/bin/python3

import serial

s = serial.Serial('/dev/ttyUSB0', 230400)
s.write(b'\xa5\x65')  # stop motor
s.close()

 

g2fre: 원하는 값으로 주파수를 변경할 수 있음. 사용법) g2fre 8.4   (8.4Hz로 주파수를 바꿔줌)

#!/bin/python3

# YDLidar G2 frequency setting example
# YDLidar G2 can change the frequency very easely unlike its brother X2, X4
# You can't get frequency set info from the lidar during scanning,
# but you can change the frequency during scanning.
# If you want to change the frequency to your desired value, when the lidir is in stop or standby mode, you can do it.
# In this example, we increase and decrease the frequency during its standby mode and scan mode.
# I noticed, right after the lidar stopped from the scan mode, 
# it used to publish its remained scan data, I guess, so I couldn't get its qrequency set info.

import sys
import serial

# increase or decrease the frequency of the lidar
# quantity: the amount you want to increase or decrease
# negative value: decrease, positive value: increase
#
# If you want to know just the frequency of the lidar, 
# you can give small amount of change value, 
# and you can get the current frequency
# Just getting the current frequency is not simple,
# because some times the lidar will give you the remained scan data instead of the frequency info.
def set_frequency(s, quantity):
  if quantity < -7 or quantity > 7:
    print("the number should be between -7 and 7")
    return
  if quantity < 0: # decrease
    quantity = abs(quantity)
    if type(quantity) == int:
      for i in range(quantity):
        s.write(b'\xa5\x0c')  # decrease the frequency by 1Hz
        read_data = s.read(DATA_SIZE)
    elif type(quantity) == float:
      count = int(quantity / 0.1)
      for i in range(count):
        s.write(b'\xa5\x0a')  # decrease the frequency by 0.1Hz
        read_data = s.read(DATA_SIZE)
  elif quantity > 0: # if increase
    if type(quantity) == int:
      for i in range(quantity):
        s.write(b'\xa5\x0b')  # increase the frequency by 1Hz
        read_data = s.read(DATA_SIZE)
    elif type(quantity) == float:
      count = int(quantity / 0.1)
      for i in range(count):
        s.write(b'\xa5\x09')  # increase the frequency by 0.1Hz
        read_data = s.read(DATA_SIZE)
    
  idx = read_data.find(b'\xa5\x5a')  # start sign
  data = read_data[idx:]
  response_mode = (data[5] >> 6) & 0b11
  if response_mode == 0: # when single response
    # get currently set scan frequency
    value = data[7] | (data[8] << 8) | (data[9] << 16) | (data[10] << 24)
    frequency = value / 100.0
    return frequency
  return 0  # something is wrong

def get_frequency(s):
  s.write(b'\xa5\x0d')
  read_data = s.read(DATA_SIZE)
  idx = read_data.find(b'\xa5\x5a')  # start sign
  data = read_data[idx:]
  response_mode = (data[5] >> 6) & 0b11
  if response_mode == 0: # when single response
    # get currently set scan frequency
    value = data[7] | (data[8] << 8) | (data[9] << 16) | (data[10] << 24)
    frequency = value / 100.0
    #print("currently set scan frequency: ", frequency)
    return frequency
  return 0  # something is wrong


def scan(s):
  s.write(b'\xa5\x60')

def stop(s):
  s.write(b'\xa5\x65')

DATA_SIZE = 11
value = float(sys.argv[1])
if (len(sys.argv) != 2) or (type(value) != int and type(value) != float):
  print(f"usage: {sys.argv[0]} frequency_you_want_to_change_to")
  exit()
if value > 12.4 or value < 5.4:
  print("frequency should be between 5.4 and 12.4")
  exit()

s = serial.Serial('/dev/ttyUSB0', 230400)

cur_frequency = get_frequency(s)
print("current scan frequency: ", cur_frequency)
amount = round(value - cur_frequency, 1)
if amount == 0.0:
  print(f"You don't need to set same frequency.")
  exit()

print("amount: ", amount)
result = set_frequency(s, amount)
print("currently set scan frequency: ", result)

stop(s)
s.close()