How to create a Telemetry Log using Pymavlink

Hi, I am trying to use the parameters from the JSBSIM engine and create a telemetry log file so i can visualize the aircraft in Mission Planner or UAV log viewer. Altough I am doing this in Python, I would like some help on creating this file.

This is my code:

def observations_to_tlog(observations, timestep_sec, output_file):
“”"
Converts an episode’s observations into a .tlog file.

Parameters:
    observations (list): A list containing observations for the entire episode.
    timestep_sec (float): Time interval between observations in seconds.
    output_file (str): Path to save the .tlog file.

Returns:
    None
"""
with open(output_file, 'wb') as tlog_file:
    

    mav = mavlink.MAVLink(tlog_file)
    mav.srcSystem = 1  # System ID
    mav.srcComponent = 1  # Component ID

    current_time_ms = 0  # Time since start, in milliseconds
    
    step=1
    for values in observations:

        current_time_ms += int(timestep_sec * 1000)  # Add timestep in milliseconds

        # Extracting the values from observation
        current_roll = values[0]  # Roll in radians
        current_pitch = values[1]  # Pitch in radians
        current_yaw = values[2]  # Yaw in radians
        current_altitude = int(values[4] * 1000)  # Altitude (AGL) in millimeters
        current_altitude_msl = int(values[8] * 1000)  # Altitude (MSL) in millimeters
        current_lat = int(values[9] * 1e7)  # Latitude in 1E-7 degrees
        current_lon = int(values[10] * 1e7)  # Longitude in 1E-7 degrees
        velocity_north = int(values[11])  # North velocity in cm/s
        velocity_east = int(values[12])  # East velocity in cm/s
        velocity_down = int(values[13])  # Down velocity in cm/s
        ground_speed = int(values[14])  # Ground speed in cm/s
        heading = int(values[15]) % 36000  # Heading in centi-degrees
        roll_speed = values[16]  # Roll rate in rad/s
        pitch_speed = values[17]  # Pitch rate in rad/s
        yaw_speed = values[18]  # Yaw rate in rad/s

        # Sending HEARTBEAT message every 5 steps
        if step % 5 == 0:
            heartbeat_msg = mavlink.MAVLink_heartbeat_message(
                type=mavlink.MAV_TYPE_FIXED_WING,
                autopilot=mavlink.MAV_AUTOPILOT_GENERIC,
                base_mode=0,
                custom_mode=0,
                system_status=mavlink.MAV_STATE_ACTIVE,
                mavlink_version=3
            )
            mav.send(heartbeat_msg)

        # GPS_RAW_INT message
        gps_msg = mavlink.MAVLink_gps_raw_int_message(
            time_usec=current_time_ms * 1000,  # Time in microseconds
            fix_type=3,  # 3 = 3D Fix
            lat=current_lat,
            lon=current_lon,
            alt=current_altitude_msl,
            eph=50,  # Horizontal dilution (cm)
            epv=50,  # Vertical dilution (cm)
            vel=ground_speed,  # Ground speed (cm/s)
            cog=heading,  # Course over ground (centidegrees)
            satellites_visible=10  # Number of satellites
        )
        mav.send(gps_msg)

        # ATTITUDE message
        attitude_msg = mavlink.MAVLink_attitude_message(
            time_boot_ms=current_time_ms,  # Time in milliseconds since boot
            roll=current_roll,  # Roll in radians
            pitch=current_pitch,  # Pitch in radians
            yaw=current_yaw,  # Yaw in radians
            rollspeed=roll_speed,  # Roll rate (rad/s)
            pitchspeed=pitch_speed,  # Pitch rate (rad/s)
            yawspeed=yaw_speed  # Yaw rate (rad/s)
        )
        mav.send(attitude_msg)

        # GLOBAL_POSITION_INT message
        position_msg = mavlink.MAVLink_global_position_int_message(
            time_boot_ms=current_time_ms,  # Time in milliseconds since boot
            lat=current_lat,
            lon=current_lon,
            alt=current_altitude_msl,
            relative_alt=current_altitude,
            vx=velocity_north,
            vy=velocity_east,
            vz=velocity_down,
            hdg=heading
        )
        mav.send(position_msg)
        step+=1
    print(f"TLog file successfully created: {os.path.abspath(output_file)}")