Skip to content

Trying to use tlog writer for my own transmissions #183

@neilyoung

Description

@neilyoung

My tlogWriter setup (snip off):

	dialectRW := &dialect.ReadWriter{Dialect: ardupilotmega.Dialect}
	err := dialectRW.Initialize()

	if err != nil {
		log.Errorf("Failed to initialize dialect: %v", err)
		return err
	}
	mc.dialectRW = dialectRW

	file, err := os.Create("output.tlog")
	if err != nil {
		return err
	}

	writer := &tlog.Writer{
		ByteWriter: file,
		DialectRW:  mc.dialectRW,
	}
	err = writer.Initialize()
	if err != nil {
		return err
	}
	mc.tlogWriter = writer

	return nil

With that output.tlog is created and I'm able to log each incoming message like so (snip off):

				if frm, ok := evt.(*gomavlib.EventFrame); ok {

					mc.logIncomingFrame(frm.Frame)

whereas

func (mc *MavlinkClient) logIncomingFrame(f frame.Frame) {
 
	if mc.tlogWriter == nil {
		return
	}

	var copy frame.Frame

	switch v := f.(type) {
	case *frame.V2Frame:
		var sig *frame.V2Signature
		if v.Signature != nil {
			s := *v.Signature
			sig = &s
		}
		copy = &frame.V2Frame{
			IncompatibilityFlag: v.IncompatibilityFlag,
			CompatibilityFlag:   v.CompatibilityFlag,
			SequenceNumber:      v.SequenceNumber,
			SystemID:            v.SystemID,
			ComponentID:         v.ComponentID,
			Message:             v.Message,
			Checksum:            v.Checksum,
			SignatureLinkID:     v.SignatureLinkID,
			SignatureTimestamp:  v.SignatureTimestamp,
			Signature:           sig,
		}
	case *frame.V1Frame:
		copy = &frame.V1Frame{
			SequenceNumber: v.SequenceNumber,
			SystemID:       v.SystemID,
			ComponentID:    v.ComponentID,
			Message:        v.Message,
			Checksum:       v.Checksum,
		}
	default:
		return
	}

	err := mc.tlogWriter.Write(&tlog.Entry{
		Time:  time.Now(),
		Frame: copy,
	})
	if err != nil {
		log.Warnf("tlog write (incoming) failed: %v", err)
	}
}

That works fine!

Now I'm trying to also log my outgoing message, so messages like this one (snip off):

	// Prepare the command message
	msg := &ardupilotmega.MessageCommandLong{
		TargetSystem:    sysID,
		TargetComponent: compID,
		Command:         cmd,
		Confirmation:    0,
	}

	log.Infof("Sending COMMAND_LONG msgID=%d type=%T", msg.GetID(), msg)

	if p.Params.Param1 != nil {
		msg.Param1 = float32(*p.Params.Param1)
	}
	if p.Params.Param2 != nil {
		msg.Param2 = float32(*p.Params.Param2)
	}
	if p.Params.Param3 != nil {
		msg.Param3 = float32(*p.Params.Param3)
	}
	if p.Params.Param4 != nil {
		msg.Param4 = float32(*p.Params.Param4)
	}
	if p.Params.Param5 != nil {
		msg.Param5 = float32(*p.Params.Param5)
	}
	if p.Params.Param6 != nil {
		msg.Param6 = float32(*p.Params.Param6)
	}
	if p.Params.Param7 != nil {
		msg.Param7 = float32(*p.Params.Param7)
	}

	mc.logOutgoingMessage(msg)

whereas

func (mc *MavlinkClient) logOutgoingMessage(msg message.Message) {
	if mc.tlogWriter == nil {
		return
	}

	fr := &frame.V2Frame{
		SystemID:    mc.sysID,    
		ComponentID: mc.compID,    
		Message:     msg,          
	}

	
	err := mc.tlogWriter.Write(&tlog.Entry{
		Time:  time.Now(),
		Frame: fr, 
	})
	if err != nil {
		log.Warnf("tlog write failed: %v", err)
	}
}

I'm getting a log entry, for instance when sending the ARM command, but mavlogdump.py complains about missing/wrong CRC:

2025-05-22 22:03:58.83: BAD_DATA {invalid MAVLink CRC in msgID 76 0x0000 should be 0xf33b, data:['fd', '20', '0', '0', '0', '1', '1', '4c', '0', '0', '0', '0', '80', '3f', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '0', '90', '1', '1', '1', '0', '0']}

Can somebody give me a pointer, how to create an entry with a valid CRC?

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions