Example: 07-Interface-Library/02-MAVLink/mavlink_opticalflow.py

# 本作品采用MIT许可证授权。
# 版权所有 (c) 2013-2023 OpenMV LLC。保留所有权利。
# https://github.com/openmv/openmv/blob/master/LICENSE
#
# MAVLink光流脚本。
#
# 该脚本使用MAVLink协议发送光流检测到
# ArduPilot/PixHawk控制器,使用您的OpenMV Cam进行位置控制。
#
# P4 = 发送数据线

import sensor
import struct
import time
import machine

UART_BAUDRATE = 115200
MAV_system_id = 1
MAV_component_id = 0x54
packet_sequence = 0

# Below 0.1 or so (YMMV) and the results are just noise.
MAV_OPTICAL_FLOW_confidence_threshold = (0.1)

# LED控制
led = machine.LED("LED_BLUE")
led_state = 0


def update_led():
    global led_state
    led_state = led_state + 1
    if led_state == 10:
        led.on()
    elif led_state >= 20:
        led.off()
        led_state = 0


# 链接设置
uart = machine.UART(3, UART_BAUDRATE, timeout_char=1000)


# https://github.com/mavlink/c_library_v1/blob/master/checksum.h
def checksum(data, extra):
    output = 0xFFFF
    for i in range(len(data)):
        tmp = data[i] ^ (output & 0xFF)
        tmp = (tmp ^ (tmp << 4)) & 0xFF
        output = ((output >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4)) & 0xFFFF
    tmp = extra ^ (output & 0xFF)
    tmp = (tmp ^ (tmp << 4)) & 0xFF
    output = ((output >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4)) & 0xFFFF
    return output


MAV_OPTICAL_FLOW_message_id = 100
MAV_OPTICAL_FLOW_id = 0  # 未使用
MAV_OPTICAL_FLOW_extra_crc = 175


# http://mavlink.org/messages/common#OPTICAL_FLOW
# https://github.com/mavlink/c_library_v1/blob/master/common/mavlink_msg_optical_flow.h
def send_optical_flow_packet(x, y, c):
    global packet_sequence
    temp = struct.pack(
        "<qfffhhbb", 0, 0, 0, 0, int(x), int(y), MAV_OPTICAL_FLOW_id, int(c * 255)
    )
    temp = struct.pack(
        "<bbbbb26s",
        26,
        packet_sequence & 0xFF,
        MAV_system_id,
        MAV_component_id,
        MAV_OPTICAL_FLOW_message_id,
        temp,
    )
    temp = struct.pack("<b31sh", 0xFE, temp, checksum(temp, MAV_OPTICAL_FLOW_extra_crc))
    packet_sequence += 1
    uart.write(temp)
    update_led()


sensor.reset()  # 重置并初始化传感器。
sensor.set_pixformat(sensor.RGB565)  # 将像素格式设置为RGB565 (or GRAYSCALE)
sensor.set_framesize(sensor.B64X32)  # 将帧大小设置为64x32...(或64x64)...
sensor.skip_frames(time=2000)  # 等待设置生效。
clock = time.clock()  # 创建一个时钟对象来跟踪FPS。

# Take from the main frame buffer's RAM to allocate a second frame buffer.
# There's a lot more RAM in the frame buffer than in the MicroPython heap.
# However, after doing this you have a lot less RAM for some algorithms...
# So, be aware that it's a lot easier to get out of RAM issues now.
extra_fb = sensor.alloc_extra_fb(sensor.width(), sensor.height(), sensor.RGB565)
extra_fb.replace(sensor.snapshot())

while True:
    clock.tick()  # Track elapsed milliseconds between snapshots().
    img = sensor.snapshot()  # 拍照并返回图像。

    displacement = extra_fb.find_displacement(img)
    extra_fb.replace(img)

    # Offset results are noisy without filtering so we drop some accuracy.
    sub_pixel_x = int(-displacement.x_translation() * 35)
    sub_pixel_y = int(displacement.y_translation() * 53)

    send_optical_flow_packet(sub_pixel_x, sub_pixel_y, displacement.response())

    print(
        "{0:+f}x {1:+f}y {2} {3} FPS".format(
            sub_pixel_x, sub_pixel_y, displacement.response(), clock.fps()
        )
    )

results matching ""

    No results matching ""