Connecting GCS to FC with pymavlink

Hi.
I bought SIYI FM30 transmitter and FR mini receiver and using its DATALINK(Telemetry) to connect GCS to FC(CUAV-X7+).
FM30 datalink protocol is Bluetooth and when I want to use it, I should connect to it with Bluetooth. When I connect to FM30 transmitter, appears 2 different COM port(for example COM11 and COM12). When I try to connect COM11 with below code it works fine.

import serial
from pymavlink import mavutil

myport = 'COM12'
mybaudrate = 115200

# Start a connection listening on a USB port
the_connection = mavutil.mavlink_connection(myport,mybaudrate)

# Wait for the first heartbeat 
#   This sets the system and component ID of remote system for the link
the_connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (the_connection.target_system, the_connection.target_component))

# Once connected, use 'the_connection' to get and send messages
the_connection.mav.request_data_stream_send(the_connection.target_system, the_connection.target_component, mavutil.mavlink.MAV_DATA_STREAM_ALL,
    10,  # Hz
    1,   # enable
    )

while 1:
    msg = the_connection.recv_match(type='STATUSTEXT', blocking=True)
    print(msg)

But when I want to connect to COM12 port with same code, it stuck on that and I can’t do anything(can’t receive heartbeat and my code stop working(not responding message appears))!!
My BIG problem is every single time I reconnect to transmitter with Bluetooth, COM ports change! and I should to rewrite all codes and change COM port in that!
Also when I connect FC directly to PC with USB-TYPE C cable, appears two COM ports. For example COM5 and COM6. One of them name is COM5 ArduPilot MAVLink and other is COM6 ArduPilot SCLAN! It connect successfully with COM5 and can’t connect with COM6!
Are my problem same as with that?
Is there anyway to Hide the SCLAN COM port(I mean only MAVLink COM port appears) or any other solution for fix this problem?

Regards, Joe

@stephendade
Do you seen that before?

pymavlink has a filtering function that can help:

from pymavlink import mavutil

preferred_ports = [
    '*FTDI*',
    "*Arduino_Mega_2560*",
    "*3D*",
    "*USB_to_UART*",
    '*Ardu*',
    '*PX4*',
    '*Hex_*',
    '*Holybro_*',
    '*mRo*',
    '*FMU*',
    '*Swift-Flyer*',
    '*Serial*',
    '*CubePilot*',
    '*Qiotek*',
]

serial_list = mavutil.auto_detect_serial(preferred_list=preferred_ports)
serial_list.sort(key=lambda x: x.device)

print('Auto-detected serial ports are:')
for port in serial_list:
    if "SLCAN" not in port.description:
        print("{0}, {1}, {2}".format(port.device, port.hwid, port.description))