hybridgroup.gobot/platforms/mavlink
Thomas Kohler 10dabf1ce5
mavlink: fix linter issues of errcheck (#959)
2023-06-14 20:08:02 +02:00
..
common mavlink: fix linter issues of errcheck (#959) 2023-06-14 20:08:02 +02:00
LICENSE Build(v2): revert move to v2 subfolder (#932) 2023-05-29 19:23:28 +02:00
README.md mavlink: fix linter issues of errcheck (#959) 2023-06-14 20:08:02 +02:00
doc.go core(build): CLI removed (#946) 2023-06-04 18:36:55 +02:00
mavlink_adaptor.go Build(v2): revert move to v2 subfolder (#932) 2023-05-29 19:23:28 +02:00
mavlink_adaptor_test.go Build(v2): revert move to v2 subfolder (#932) 2023-05-29 19:23:28 +02:00
mavlink_driver.go Build(v2): revert move to v2 subfolder (#932) 2023-05-29 19:23:28 +02:00
mavlink_driver_test.go all(style) : fix linter issues for errcheck, ineffassign, unused and fix errors (#950) 2023-06-12 19:51:25 +02:00
mavlink_udp_adaptor.go Build(v2): revert move to v2 subfolder (#932) 2023-05-29 19:23:28 +02:00
mavlink_udp_adaptor_test.go all(style) : fix linter issues for errcheck, ineffassign, unused and fix errors (#950) 2023-06-12 19:51:25 +02:00

README.md

Mavlink

For information on the MAVlink communication protocol click here.

This package supports Mavlink over serial (such as a SiK modem) and Mavlink over UDP (such as via mavproxy). Serial is useful for point to point links, and UDP is useful for where you have multiple simultaneous clients such as the robot and QGroundControl.

As at 2018-04, this package supports Mavlink 1.0 only. If the robot doesn't receiving data then check that the other devices are configured to send version 1.0 frames.

For Mavlink 2.0 please refer to gomavlib.

How to Install

Please refer to the main README.md

How to Use

package main

import (
  "fmt"

  "gobot.io/x/gobot/v2"
  "gobot.io/x/gobot/v2/platforms/mavlink"
  common "gobot.io/x/gobot/v2/platforms/mavlink/common"
)

func main() {
  adaptor := mavlink.NewAdaptor("/dev/ttyACM0")
  iris := mavlink.NewDriver(adaptor)

  work := func() {
    iris.Once(iris.Event("packet"), func(data interface{}) {
      packet := data.(*common.MAVLinkPacket)

      dataStream := common.NewRequestDataStream(100,
        packet.SystemID,
        packet.ComponentID,
        4,
        1,
      )
      iris.SendPacket(common.CraftMAVLinkPacket(packet.SystemID,
        packet.ComponentID,
        dataStream,
      ))
    })

    iris.On(iris.Event("message"), func(data interface{}) {
      if data.(common.MAVLinkMessage).Id() == 30 {
        message := data.(*common.Attitude)
        fmt.Println("Attitude")
        fmt.Println("TIME_BOOT_MS", message.TIME_BOOT_MS)
        fmt.Println("ROLL", message.ROLL)
        fmt.Println("PITCH", message.PITCH)
        fmt.Println("YAW", message.YAW)
        fmt.Println("ROLLSPEED", message.ROLLSPEED)
        fmt.Println("PITCHSPEED", message.PITCHSPEED)
        fmt.Println("YAWSPEED", message.YAWSPEED)
        fmt.Println("")
      }
    })
  }

  robot := gobot.NewRobot("mavBot",
    []gobot.Connection{adaptor},
    []gobot.Device{iris},
    work,
  )

  robot.Start()
}

How to use: UDP

  adaptor := mavlink.NewUDPAdaptor(":14550")

To test, install Mavproxy and set it up to listen on serial and repeat over UDP:

$ mavproxy.py --out=udpbcast:192.168.0.255:14550

Change the address to the broadcast address of your subnet.