gobot

package module
v2.3.0 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Jan 7, 2024 License: Apache-2.0 Imports: 15 Imported by: 5

README

Gobot

GoDoc CircleCI Build status Appveyor Build status codecov Go Report Card License

Gobot (https://gobot.io/) is a framework using the Go programming language (https://golang.org/) for robotics, physical computing, and the Internet of Things.

It provides a simple, yet powerful way to create solutions that incorporate multiple, different hardware devices at the same time.

Want to run Go directly on microcontrollers? Check out our sister project TinyGo (https://tinygo.org/)

Getting Started

Get in touch

Get the Gobot source code by running this commands:

git clone https://github.com/hybridgroup/gobot.git
git checkout release

Afterwards have a look at the examples directory. You need to find an example matching your platform for your first test (e.g. "raspi_blink.go"). Than build the binary (cross compile), transfer it to your target and run it.

env GOOS=linux GOARCH=arm GOARM=5 go build -o ./output/my_raspi_bink examples/raspi_blink.go

Building the code on your local machine with the example code above will create a binary for ARMv5. This is probably not what you need for your specific target platform. Please read also the platform specific documentation in the platform subfolders.

Create your first project

Create a new folder and a new Go module project.

mkdir ~/my_gobot_example
cd ~/my_gobot_example
go mod init my.gobot.example.com

Copy your example file besides the go.mod file, import the requirements and build.

cp /<path to gobot folder>/examples/raspi_blink.go ~/my_gobot_example/
go mod tidy
env GOOS=linux GOARCH=arm GOARM=5 go build -o ./output/my_raspi_bink raspi_blink.go

Now you are ready to modify the example and test your changes. Start by removing the build directives at the beginning of the file.

Examples

Gobot with Arduino

package main

import (
  "time"

  "gobot.io/x/gobot/v2"
  "gobot.io/x/gobot/v2/drivers/gpio"
  "gobot.io/x/gobot/v2/platforms/firmata"
)

func main() {
  firmataAdaptor := firmata.NewAdaptor("/dev/ttyACM0")
  led := gpio.NewLedDriver(firmataAdaptor, "13")

  work := func() {
    gobot.Every(1*time.Second, func() {
      led.Toggle()
    })
  }

  robot := gobot.NewRobot("bot",
    []gobot.Connection{firmataAdaptor},
    []gobot.Device{led},
    work,
  )

  robot.Start()
}

Gobot with Sphero

package main

import (
  "fmt"
  "time"

  "gobot.io/x/gobot/v2"
  "gobot.io/x/gobot/v2/platforms/sphero"
)

func main() {
  adaptor := sphero.NewAdaptor("/dev/rfcomm0")
  driver := sphero.NewSpheroDriver(adaptor)

  work := func() {
    gobot.Every(3*time.Second, func() {
      driver.Roll(30, uint16(gobot.Rand(360)))
    })
  }

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

  robot.Start()
}

"Metal" Gobot

You can use the entire Gobot framework as shown in the examples above ("Classic" Gobot), or you can pick and choose from the various Gobot packages to control hardware with nothing but pure idiomatic Golang code ("Metal" Gobot). For example:

package main

import (
  "gobot.io/x/gobot/v2/drivers/gpio"
  "gobot.io/x/gobot/v2/platforms/intel-iot/edison"
  "time"
)

func main() {
  e := edison.NewAdaptor()
  e.Connect()

  led := gpio.NewLedDriver(e, "13")
  led.Start()

  for {
    led.Toggle()
    time.Sleep(1000 * time.Millisecond)
  }
}

"Master" Gobot

You can also use the full capabilities of the framework aka "Master Gobot" to control swarms of robots or other features such as the built-in API server. For example:

package main

import (
  "fmt"
  "time"

  "gobot.io/x/gobot/v2"
  "gobot.io/x/gobot/v2/api"
  "gobot.io/x/gobot/v2/platforms/sphero"
)

func NewSwarmBot(port string) *gobot.Robot {
  spheroAdaptor := sphero.NewAdaptor(port)
  spheroDriver := sphero.NewSpheroDriver(spheroAdaptor)
  spheroDriver.SetName("Sphero" + port)

  work := func() {
    spheroDriver.Stop()

    spheroDriver.On(sphero.Collision, func(data interface{}) {
      fmt.Println("Collision Detected!")
    })

    gobot.Every(1*time.Second, func() {
      spheroDriver.Roll(100, uint16(gobot.Rand(360)))
    })
    gobot.Every(3*time.Second, func() {
      spheroDriver.SetRGB(uint8(gobot.Rand(255)),
        uint8(gobot.Rand(255)),
        uint8(gobot.Rand(255)),
      )
    })
  }

  robot := gobot.NewRobot("sphero",
    []gobot.Connection{spheroAdaptor},
    []gobot.Device{spheroDriver},
    work,
  )

  return robot
}

func main() {
  master := gobot.NewMaster()
  api.NewAPI(master).Start()

  spheros := []string{
    "/dev/rfcomm0",
    "/dev/rfcomm1",
    "/dev/rfcomm2",
    "/dev/rfcomm3",
  }

  for _, port := range spheros {
    master.AddRobot(NewSwarmBot(port))
  }

  master.Start()
}

Hardware Support

Gobot has a extensible system for connecting to hardware devices. The following robotics and physical computing platforms are currently supported:

Support for many devices that use General Purpose Input/Output (GPIO) have a shared set of drivers provided using the gobot/drivers/gpio package:

  • GPIO <=> Drivers
    • AIP1640 LED Dot Matrix/7 Segment Controller
    • Button
    • Buzzer
    • Direct Pin
    • EasyDriver
    • Grove Button (by using driver for Button)
    • Grove Buzzer (by using driver for Buzzer)
    • Grove LED (by using driver for LED)
    • Grove Magnetic Switch (by using driver for Button)
    • Grove Relay (by using driver for Relay)
    • Grove Touch Sensor (by using driver for Button)
    • HC-SR04 Ultrasonic Ranging Module
    • HD44780 LCD controller
    • LED
    • Makey Button (by using driver for Button)
    • MAX7219 LED Dot Matrix
    • Motor
    • Proximity Infra Red (PIR) Motion Sensor
    • Relay
    • RGB LED
    • Servo
    • Stepper Motor
    • TM1638 LED Controller

Support for many devices that use Analog Input/Output (AIO) have a shared set of drivers provided using the gobot/drivers/aio package:

  • AIO <=> Drivers
    • Analog Actuator
    • Analog Sensor
    • Grove Light Sensor
    • Grove Piezo Vibration Sensor
    • Grove Rotary Dial
    • Grove Sound Sensor
    • Grove Temperature Sensor
    • Temperature Sensor (supports linear and NTC thermistor in normal and inverse mode)
    • Thermal Zone Temperature Sensor

Support for devices that use Inter-Integrated Circuit (I2C) have a shared set of drivers provided using the gobot/drivers/i2c package:

  • I2C <=> Drivers
    • Adafruit 1109 2x16 RGB-LCD with 5 keys
    • Adafruit 2327 16-Channel PWM/Servo HAT Hat
    • Adafruit 2348 DC and Stepper Motor Hat
    • ADS1015 Analog to Digital Converter
    • ADS1115 Analog to Digital Converter
    • ADXL345 Digital Accelerometer
    • BH1750 Digital Luminosity/Lux/Light Sensor
    • BlinkM LED
    • BME280 Barometric Pressure/Temperature/Altitude/Humidity Sensor
    • BMP180 Barometric Pressure/Temperature/Altitude Sensor
    • BMP280 Barometric Pressure/Temperature/Altitude Sensor
    • BMP388 Barometric Pressure/Temperature/Altitude Sensor
    • DRV2605L Haptic Controller
    • Generic driver for read and write values to/from register address
    • Grove Digital Accelerometer
    • GrovePi Expansion Board
    • Grove RGB LCD
    • HMC6352 Compass
    • HMC5883L 3-Axis Digital Compass
    • INA3221 Voltage Monitor
    • JHD1313M1 LCD Display w/RGB Backlight
    • L3GD20H 3-Axis Gyroscope
    • LIDAR-Lite
    • MCP23017 Port Expander
    • MMA7660 3-Axis Accelerometer
    • MPL115A2 Barometric Pressure/Temperature
    • MPU6050 Accelerometer/Gyroscope
    • PCA9501 8-bit I/O port with interrupt, 2-kbit EEPROM
    • PCA953x LED Dimmer for PCA9530 (2-bit), PCA9533 (4-bit), PCA9531 (8-bit), PCA9532 (16-bit)
    • PCA9685 16-channel 12-bit PWM/Servo Driver
    • PCF8583 clock and calendar or event counter, 240 x 8-bit RAM
    • PCF8591 8-bit 4xA/D & 1xD/A converter
    • SHT2x Temperature/Humidity
    • SHT3x-D Temperature/Humidity
    • SSD1306 OLED Display Controller
    • TSL2561 Digital Luminosity/Lux/Light Sensor
    • Wii Nunchuck Controller
    • YL-40 Brightness/Temperature sensor, Potentiometer, analog input, analog output Driver

Support for devices that use Serial Peripheral Interface (SPI) have a shared set of drivers provided using the gobot/drivers/spi package:

  • SPI <=> Drivers
    • APA102 Programmable LEDs
    • MCP3002 Analog/Digital Converter
    • MCP3004 Analog/Digital Converter
    • MCP3008 Analog/Digital Converter
    • MCP3202 Analog/Digital Converter
    • MCP3204 Analog/Digital Converter
    • MCP3208 Analog/Digital Converter
    • MCP3304 Analog/Digital Converter
    • MFRC522 RFID Card Reader
    • SSD1306 OLED Display Controller

More platforms and drivers are coming soon...

API

Gobot includes a RESTful API to query the status of any robot running within a group, including the connection and device status, and execute device commands.

To activate the API, import the gobot.io/x/gobot/v2/api package and instantiate the API like this:

  master := gobot.NewMaster()
  api.NewAPI(master).Start()

You can also specify the api host and port, and turn on authentication:

  master := gobot.NewMaster()
  server := api.NewAPI(master)
  server.Port = "4000"
  server.AddHandler(api.BasicAuth("gort", "klatuu"))
  server.Start()

You may access the robeaux React.js interface with Gobot by navigating to http://localhost:3000/index.html.

CLI

Gobot uses the Gort http://gort.io Command Line Interface (CLI) so you can access important features right from the command line. We call it "RobotOps", aka "DevOps For Robotics". You can scan, connect, update device firmware, and more!

Documentation

We're always adding documentation to our web site at https://gobot.io/ please check there as we continue to work on Gobot

Thank you!

Need help?

Contributing

For our contribution guidelines, please go to https://github.com/hybridgroup/gobot/blob/master/CONTRIBUTING.md .

Gobot is released with a Contributor Code of Conduct. By participating in this project you agree to abide by its terms. You can read about it here.

License

Copyright (c) 2013-2020 The Hybrid Group. Licensed under the Apache 2.0 license.

The Contributor Covenant is released under the Creative Commons Attribution 4.0 International Public License, which requires that attribution be included.

Documentation

Overview

Package gobot is the primary entrypoint for Gobot (http://gobot.io), a framework for robotics, physical computing, and the Internet of Things written using the Go programming language .

It provides a simple, yet powerful way to create solutions that incorporate multiple, different hardware devices at the same time.

Classic Gobot

Here is a "Classic Gobot" program that blinks an LED using an Arduino:

package main

import (
    "time"

    "gobot.io/x/gobot/v2"
    "gobot.io/x/gobot/v2/drivers/gpio"
    "gobot.io/x/gobot/v2/platforms/firmata"
)

func main() {
    firmataAdaptor := firmata.NewAdaptor("/dev/ttyACM0")
    led := gpio.NewLedDriver(firmataAdaptor, "13")

    work := func() {
        gobot.Every(1*time.Second, func() {
            led.Toggle()
        })
    }

    robot := gobot.NewRobot("bot",
        []gobot.Connection{firmataAdaptor},
        []gobot.Device{led},
        work,
    )

    robot.Start()
}

Metal Gobot

You can also use Metal Gobot and pick and choose from the various Gobot packages to control hardware with nothing but pure idiomatic Golang code. For example:

package main

import (
    "gobot.io/x/gobot/v2/drivers/gpio"
    "gobot.io/x/gobot/v2/platforms/intel-iot/edison"
    "time"
)

func main() {
    e := edison.NewAdaptor()
    e.Connect()

    led := gpio.NewLedDriver(e, "13")
    led.Start()

    for {
        led.Toggle()
        time.Sleep(1000 * time.Millisecond)
    }
}

Master Gobot

Finally, you can use Master Gobot to add the complete Gobot API or control swarms of Robots:

package main

import (
    "fmt"
    "time"

    "gobot.io/x/gobot/v2"
    "gobot.io/x/gobot/v2/api"
    "gobot.io/x/gobot/v2/platforms/sphero"
)

func NewSwarmBot(port string) *gobot.Robot {
    spheroAdaptor := sphero.NewAdaptor(port)
    spheroDriver := sphero.NewSpheroDriver(spheroAdaptor)
    spheroDriver.SetName("Sphero" + port)

    work := func() {
        spheroDriver.Stop()

        spheroDriver.On(sphero.Collision, func(data interface{}) {
            fmt.Println("Collision Detected!")
        })

        gobot.Every(1*time.Second, func() {
            spheroDriver.Roll(100, uint16(gobot.Rand(360)))
        })
        gobot.Every(3*time.Second, func() {
            spheroDriver.SetRGB(uint8(gobot.Rand(255)),
                uint8(gobot.Rand(255)),
                uint8(gobot.Rand(255)),
            )
        })
    }

    robot := gobot.NewRobot("sphero",
        []gobot.Connection{spheroAdaptor},
        []gobot.Device{spheroDriver},
        work,
    )

    return robot
}

func main() {
    master := gobot.NewMaster()
    api.NewAPI(master).Start()

    spheros := []string{
        "/dev/rfcomm0",
        "/dev/rfcomm1",
        "/dev/rfcomm2",
        "/dev/rfcomm3",
    }

    for _, port := range spheros {
        master.AddRobot(NewSwarmBot(port))
    }

    master.Start()
}

Copyright (c) 2013-2018 The Hybrid Group. Licensed under the Apache 2.0 license.

Index

Constants

View Source
const (
	EveryWorkKind = "every"
	AfterWorkKind = "after"
)

Variables

This section is empty.

Functions

func After

func After(t time.Duration, f func())

After triggers f after t duration.

func DefaultName

func DefaultName(name string) string

DefaultName returns a sensible random default name for a robot, adaptor or driver

func Every

func Every(t time.Duration, f func()) *time.Ticker

Every triggers f every t time.Duration until the end of days, or when a Stop() is called on the Ticker that is returned by the Every function. It does not wait for the previous execution of f to finish before it fires the next f.

func FromScale

func FromScale(input, min, max float64) float64

FromScale returns a converted input from min, max to 0.0...1.0.

func Rand

func Rand(max int) int

Rand returns a positive random int up to max

func Rescale

func Rescale(input, fromMin, fromMax, toMin, toMax float64) float64

Rescale performs a direct linear rescaling of a number from one scale to another.

func ToScale

func ToScale(input, min, max float64) float64

ToScale returns a converted input from 0...1 to min...max scale. If input is less than min then ToScale returns min. If input is greater than max then ToScale returns max

Types

type Adaptor

type Adaptor interface {
	// Name returns the label for the Adaptor
	Name() string
	// SetName sets the label for the Adaptor
	SetName(name string)
	// Connect initiates the Adaptor
	Connect() error
	// Finalize terminates the Adaptor
	Finalize() error
}

Adaptor is the interface that describes an adaptor in gobot

type AnalogPinner added in v2.3.0

type AnalogPinner interface {
	// Read reads the current value of the pin
	Read() (int, error)
	// Write writes to the pin
	Write(val int) error
}

AnalogPinner is the interface for system analog io interactions

type BusOperations

type BusOperations interface {
	// ReadByteData reads a byte from the given register of bus device.
	ReadByteData(reg uint8) (uint8, error)
	// ReadBlockData fills the given buffer with reads starting from the given register of bus device.
	ReadBlockData(reg uint8, data []byte) error
	// WriteByteData writes the given byte value to the given register of bus device.
	WriteByteData(reg uint8, val uint8) error
	// WriteBlockData writes the given data starting from the given register of bus device.
	WriteBlockData(reg uint8, data []byte) error
	// WriteByte writes the given byte value to the current register of bus device.
	WriteByte(val byte) error
	// WriteBytes writes the given data starting from the current register of bus device.
	WriteBytes(data []byte) error
}

BusOperations are functions provided by a bus device, e.g. SPI, i2c.

type Commander

type Commander interface {
	// Command returns a command given a name. Returns nil if the command is not found.
	Command(name string) (command func(map[string]interface{}) interface{})
	// Commands returns a map of commands.
	Commands() (commands map[string]func(map[string]interface{}) interface{})
	// AddCommand adds a command given a name.
	AddCommand(name string, command func(map[string]interface{}) interface{})
}

Commander is the interface which describes the behaviour for a Driver or Adaptor which exposes API commands.

func NewCommander

func NewCommander() Commander

NewCommander returns a new Commander.

type Connection

type Connection Adaptor

A Connection is an instance of an Adaptor

type Connections

type Connections []Connection

Connections represents a collection of Connection

func (*Connections) Each

func (c *Connections) Each(f func(Connection))

Each enumerates through the Connections and calls specified callback function.

func (*Connections) Finalize

func (c *Connections) Finalize() error

Finalize calls Finalize on each Connection in c

func (*Connections) Len

func (c *Connections) Len() int

Len returns connections length

func (*Connections) Start

func (c *Connections) Start() error

Start calls Connect on each Connection in c

type Device

type Device Driver

A Device is an instnace of a Driver

type Devices

type Devices []Device

Devices represents a collection of Device

func (*Devices) Each

func (d *Devices) Each(f func(Device))

Each enumerates through the Devices and calls specified callback function.

func (*Devices) Halt

func (d *Devices) Halt() error

Halt calls Halt on each Device in d

func (*Devices) Len

func (d *Devices) Len() int

Len returns devices length

func (*Devices) Start

func (d *Devices) Start() error

Start calls Start on each Device in d

type DigitalPinOptionApplier

type DigitalPinOptionApplier interface {
	// ApplyOptions apply all given options to the pin immediately
	ApplyOptions(options ...func(DigitalPinOptioner) bool) error
}

DigitalPinOptionApplier is the interface to apply options to change pin behavior immediately

type DigitalPinOptioner

type DigitalPinOptioner interface {
	// SetLabel change the pins label
	SetLabel(label string) (changed bool)
	// SetDirectionOutput sets the pins direction to output with the given initial value
	SetDirectionOutput(initialState int) (changed bool)
	// SetDirectionInput sets the pins direction to input
	SetDirectionInput() (changed bool)
	// SetActiveLow initializes the pin with inverse reaction (applies on input and output).
	SetActiveLow() (changed bool)
	// SetBias initializes the pin with the given bias (applies on input and output).
	SetBias(bias int) (changed bool)
	// SetDrive initializes the output pin with the given drive option.
	SetDrive(drive int) (changed bool)
	// SetDebounce initializes the input pin with the given debounce period.
	SetDebounce(period time.Duration) (changed bool)
	// SetEventHandlerForEdge initializes the input pin for edge detection to call the event handler on specified edge.
	// lineOffset is within the GPIO chip (needs to transformed to the pin id), timestamp is the detection time,
	// detectedEdge contains the direction of the pin changes, seqno is the sequence number for this event in the sequence
	// of events for all the lines in this line request, lseqno is the same but for this line
	SetEventHandlerForEdge(handler func(lineOffset int, timestamp time.Duration, detectedEdge string, seqno uint32,
		lseqno uint32), edge int) (changed bool)
	// SetPollForEdgeDetection use a discrete input polling method to detect edges. A poll interval of zero or smaller
	// will deactivate this function. Please note: Using this feature is CPU consuming and less accurate than using cdev
	// event handler (gpiod implementation) and should be done only if the former is not implemented or not working for
	// the adaptor. E.g. sysfs driver in gobot has not implemented edge detection yet. The function is only useful
	// together with SetEventHandlerForEdge() and its corresponding With*() functions.
	SetPollForEdgeDetection(pollInterval time.Duration, pollQuitChan chan struct{}) (changed bool)
}

DigitalPinOptioner is the interface to provide the possibility to change pin behavior for the next usage

type DigitalPinValuer

type DigitalPinValuer interface {
	// DirectionBehavior gets the direction behavior when the pin is used the next time.
	// This means its possibly not in this direction type at the moment.
	DirectionBehavior() string
}

DigitalPinValuer is the interface to get pin behavior for the next usage. The interface is and should be rarely used.

type DigitalPinner

type DigitalPinner interface {
	// Export exports the pin for use by the adaptor
	Export() error
	// Unexport releases the pin from the adaptor, so it is free for the operating system
	Unexport() error
	// Read reads the current value of the pin
	Read() (int, error)
	// Write writes to the pin
	Write(val int) error
	// DigitalPinOptionApplier is the interface to change pin behavior immediately
	DigitalPinOptionApplier
}

DigitalPinner is the interface for system gpio interactions

type DigitalPinnerProvider

type DigitalPinnerProvider interface {
	DigitalPin(id string) (DigitalPinner, error)
}

DigitalPinnerProvider is the interface that an Adaptor should implement to allow clients to obtain access to any DigitalPin's available on that board. If the pin is initially acquired, it is an input. Pin direction and other options can be changed afterwards by pin.ApplyOptions() at any time.

type Driver

type Driver interface {
	// Name returns the label for the Driver
	Name() string
	// SetName sets the label for the Driver.
	// Please prefer to use options [gpio.WithName or aio.WithName] instead, if possible.
	SetName(s string)
	// Start initiates the Driver
	Start() error
	// Halt terminates the Driver
	Halt() error
	// Connection returns the Connection associated with the Driver
	Connection() Connection
}

Driver is the interface that describes a driver in gobot

type Event

type Event struct {
	Name string
	Data interface{}
}

Event represents when something asynchronous happens in a Driver or Adaptor

func NewEvent

func NewEvent(name string, data interface{}) *Event

NewEvent returns a new Event and its associated data.

type Eventer

type Eventer interface {
	// Events returns the map of valid Event names.
	Events() (eventnames map[string]string)

	// Event returns an Event string from map of valid Event names.
	// Mostly used to validate that an Event name is valid.
	Event(name string) string

	// AddEvent registers a new Event name.
	AddEvent(name string)

	// DeleteEvent removes a previously registered Event name.
	DeleteEvent(name string)

	// Publish new events to any subscriber
	Publish(name string, data interface{})

	// Subscribe to events
	Subscribe() (events eventChannel)

	// Unsubscribe from an event channel
	Unsubscribe(events eventChannel)

	// Event handler
	On(name string, f func(s interface{})) error

	// Event handler, only executes one time
	Once(name string, f func(s interface{})) error
}

Eventer is the interface which describes how a Driver or Adaptor handles events.

func NewEventer

func NewEventer() Eventer

NewEventer returns a new Eventer.

type I2cOperations

type I2cOperations interface {
	io.ReadWriteCloser
	BusOperations
	// ReadByte reads a byte from the current register of an i2c device.
	ReadByte() (byte, error)
	// ReadWordData reads a 16 bit value starting from the given register of an i2c device.
	ReadWordData(reg uint8) (uint16, error)
	// WriteWordData writes the given 16 bit value starting from the given register of an i2c device.
	WriteWordData(reg uint8, val uint16) error
}

I2cOperations represents the i2c methods according to I2C/SMBus specification.

type I2cSystemDevicer

type I2cSystemDevicer interface {
	// ReadByte must be implemented as the sequence:
	// "S Addr Rd [A] [Data] NA P"
	ReadByte(address int) (byte, error)

	// ReadByteData must be implemented as the sequence:
	// "S Addr Wr [A] Comm [A] Sr Addr Rd [A] [Data] NA P"
	ReadByteData(address int, reg uint8) (uint8, error)

	// ReadWordData must be implemented as the sequence:
	// "S Addr Wr [A] Comm [A] Sr Addr Rd [A] [DataLow] A [DataHigh] NA P"
	ReadWordData(address int, reg uint8) (uint16, error)

	// ReadBlockData must be implemented as the sequence:
	// "S Addr Wr [A] Comm [A] Sr Addr Rd [A] [Count] A [Data] A [Data] A ... A [Data] NA P"
	ReadBlockData(address int, reg uint8, data []byte) error

	// WriteByte must be implemented as the sequence:
	// "S Addr Wr [A] Data [A] P"
	WriteByte(address int, val byte) error

	// WriteByteData must be implemented as the sequence:
	// "S Addr Wr [A] Comm [A] Data [A] P"
	WriteByteData(address int, reg uint8, val uint8) error

	// WriteBlockData must be implemented as the sequence:
	// "S Addr Wr [A] Comm [A] Count [A] Data [A] Data [A] ... [A] Data [A] P"
	WriteBlockData(address int, reg uint8, data []byte) error

	// WriteWordData must be implemented as the sequence:
	// "S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] P"
	WriteWordData(address int, reg uint8, val uint16) error

	// WriteBytes writes the given data starting from the current register of bus device.
	WriteBytes(address int, data []byte) error

	// Read implements direct read operations.
	Read(address int, b []byte) (int, error)

	// Write implements direct write operations.
	Write(address int, b []byte) (n int, err error)

	// Close closes the character device file.
	Close() error
}

I2cSystemDevicer is the interface to a i2c bus at system level, according to I2C/SMBus specification. Some functions are not in the interface yet: * Process Call (WriteWordDataReadWordData) * Block Write - Block Read (WriteBlockDataReadBlockData) * Host Notify - WriteWordData() can be used instead

see: https://docs.kernel.org/i2c/smbus-protocol.html#key-to-symbols

S: Start condition; Sr: Repeated start condition, used to switch from write to read mode. P: Stop condition; Rd/Wr (1 bit): Read/Write bit. Rd equals 1, Wr equals 0. A, NA (1 bit): Acknowledge (ACK) and Not Acknowledge (NACK) bit Addr (7 bits): I2C 7 bit address. (10 bit I2C address not yet supported by gobot). Comm (8 bits): Command byte, a data byte which often selects a register on the device. Data (8 bits): A plain data byte. DataLow and DataHigh represent the low and high byte of a 16 bit word. Count (8 bits): A data byte containing the length of a block operation. [..]: Data sent by I2C device, as opposed to data sent by the host adapter.

type JSONConnection

type JSONConnection struct {
	Name    string `json:"name"`
	Adaptor string `json:"adaptor"`
}

JSONConnection is a JSON representation of a Connection.

func NewJSONConnection

func NewJSONConnection(connection Connection) *JSONConnection

NewJSONConnection returns a JSONConnection given a Connection.

type JSONDevice

type JSONDevice struct {
	Name       string   `json:"name"`
	Driver     string   `json:"driver"`
	Connection string   `json:"connection"`
	Commands   []string `json:"commands"`
}

JSONDevice is a JSON representation of a Device.

func NewJSONDevice

func NewJSONDevice(device Device) *JSONDevice

NewJSONDevice returns a JSONDevice given a Device.

type JSONMaster

type JSONMaster struct {
	Robots   []*JSONRobot `json:"robots"`
	Commands []string     `json:"commands"`
}

JSONMaster is a JSON representation of a Gobot Master.

func NewJSONMaster

func NewJSONMaster(gobot *Master) *JSONMaster

NewJSONMaster returns a JSONMaster given a Gobot Master.

type JSONRobot

type JSONRobot struct {
	Name        string            `json:"name"`
	Commands    []string          `json:"commands"`
	Connections []*JSONConnection `json:"connections"`
	Devices     []*JSONDevice     `json:"devices"`
}

JSONRobot a JSON representation of a Robot.

func NewJSONRobot

func NewJSONRobot(robot *Robot) *JSONRobot

NewJSONRobot returns a JSONRobot given a Robot.

type Master

type Master struct {
	AutoRun bool

	Commander
	Eventer
	// contains filtered or unexported fields
}

Master is the main type of your Gobot application and contains a collection of Robots, API commands that apply to the Master, and Events that apply to the Master.

func NewMaster

func NewMaster() *Master

NewMaster returns a new Gobot Master

func (*Master) AddRobot

func (g *Master) AddRobot(r *Robot) *Robot

AddRobot adds a new robot to the internal collection of robots. Returns the added robot

func (*Master) Robot

func (g *Master) Robot(name string) *Robot

Robot returns a robot given name. Returns nil if the Robot does not exist.

func (*Master) Robots

func (g *Master) Robots() *Robots

Robots returns all robots associated with this Gobot Master.

func (*Master) Running

func (g *Master) Running() bool

Running returns if the Master is currently started or not

func (*Master) Start

func (g *Master) Start() error

Start calls the Start method on each robot in its collection of robots. On error, call Stop to ensure that all robots are returned to a sane, stopped state.

func (*Master) Stop

func (g *Master) Stop() error

Stop calls the Stop method on each robot in its collection of robots.

type PWMPinner

type PWMPinner interface {
	// Export exports the PWM pin for use by the operating system
	Export() error
	// Unexport releases the PWM pin from the operating system
	Unexport() error
	// Enabled returns the enabled state of the PWM pin
	Enabled() (bool, error)
	// SetEnabled enables/disables the PWM pin
	SetEnabled(val bool) error
	// Polarity returns true if the polarity of the PWM pin is normal, otherwise false
	Polarity() (bool, error)
	// SetPolarity sets the polarity of the PWM pin to normal if called with true and to inverted if called with false
	SetPolarity(normal bool) error
	// Period returns the current PWM period in nanoseconds for pin
	Period() (uint32, error)
	// SetPeriod sets the current PWM period in nanoseconds for pin
	SetPeriod(period uint32) error
	// DutyCycle returns the duty cycle in nanoseconds for the PWM pin
	DutyCycle() (uint32, error)
	// SetDutyCycle writes the duty cycle in nanoseconds to the PWM pin
	SetDutyCycle(dutyCyle uint32) error
}

PWMPinner is the interface for system PWM interactions

type PWMPinnerProvider

type PWMPinnerProvider interface {
	PWMPin(id string) (PWMPinner, error)
}

PWMPinnerProvider is the interface that an Adaptor should implement to allow clients to obtain access to any PWMPin's available on that board.

type Pinner

type Pinner interface {
	Pin() string
}

Pinner is the interface that describes a driver's pin

type Porter

type Porter interface {
	Port() string
}

Porter is the interface that describes an adaptor's port

type Robot

type Robot struct {
	Name string
	Work func()

	AutoRun bool

	WorkEveryWaitGroup *sync.WaitGroup
	WorkAfterWaitGroup *sync.WaitGroup
	Commander
	Eventer
	// contains filtered or unexported fields
}

Robot is a named entity that manages a collection of connections and devices. It contains its own work routine and a collection of custom commands to control a robot remotely via the Gobot api.

func NewRobot

func NewRobot(v ...interface{}) *Robot

NewRobot returns a new Robot. It supports the following optional params:

name:	string with the name of the Robot. A name will be automatically generated if no name is supplied.
[]Connection: Connections which are automatically started and stopped with the robot
[]Device: Devices which are automatically started and stopped with the robot
func(): The work routine the robot will execute once all devices and connections have been initialized and started

func (*Robot) AddConnection

func (r *Robot) AddConnection(c Connection) Connection

AddConnection adds a new connection to the robots collection of connections. Returns the added connection.

func (*Robot) AddDevice

func (r *Robot) AddDevice(d Device) Device

AddDevice adds a new Device to the robots collection of devices. Returns the added device.

func (*Robot) After

func (r *Robot) After(ctx context.Context, d time.Duration, f func()) *RobotWork

After calls the given function after the provided duration has elapsed

func (*Robot) Connection

func (r *Robot) Connection(name string) Connection

Connection returns a connection given a name. Returns nil if the Connection does not exist.

func (*Robot) Connections

func (r *Robot) Connections() *Connections

Connections returns all connections associated with this robot.

func (*Robot) Device

func (r *Robot) Device(name string) Device

Device returns a device given a name. Returns nil if the Device does not exist.

func (*Robot) Devices

func (r *Robot) Devices() *Devices

Devices returns all devices associated with this Robot.

func (*Robot) Every

func (r *Robot) Every(ctx context.Context, d time.Duration, f func()) *RobotWork

Every calls the given function for every tick of the provided duration.

func (*Robot) Running

func (r *Robot) Running() bool

Running returns if the Robot is currently started or not

func (*Robot) Start

func (r *Robot) Start(args ...interface{}) error

Start a Robot's Connections, Devices, and work. We stop initialization of connections and devices on first error.

func (*Robot) Stop

func (r *Robot) Stop() error

Stop stops a Robot's connections and devices. We try to stop all items and collect all errors.

func (*Robot) WorkRegistry

func (r *Robot) WorkRegistry() *RobotWorkRegistry

WorkRegistry returns the Robot's WorkRegistry

type RobotWork

type RobotWork struct {
	// contains filtered or unexported fields
}

RobotWork and the RobotWork registry represent units of executing computation managed at the Robot level. Unlike the utility functions gobot.After and gobot.Every, RobotWork units require a context.Context, and can be cancelled externally by calling code.

Usage:

someWork := myRobot.Every(context.Background(), time.Second * 2, func(){
	fmt.Println("Here I am doing work")
})

someWork.CallCancelFunc() // Cancel next tick and remove from work registry

goroutines for Every and After are run on their own WaitGroups for synchronization:

someWork2 := myRobot.Every(context.Background(), time.Second * 2, func(){
	fmt.Println("Here I am doing more work")
})

somework2.CallCancelFunc()

// wait for both Every calls to finish
robot.WorkEveryWaitGroup().Wait()

func (*RobotWork) CallCancelFunc

func (rw *RobotWork) CallCancelFunc()

CallCancelFunc calls the context.CancelFunc used to cancel the work

func (*RobotWork) CancelFunc

func (rw *RobotWork) CancelFunc() context.CancelFunc

CancelFunc returns the context.CancelFunc used to cancel the work

func (*RobotWork) Duration

func (rw *RobotWork) Duration() time.Duration

Duration returns the timeout until an After fires or the period of an Every

func (*RobotWork) ID

func (rw *RobotWork) ID() uuid.UUID

ID returns the UUID of the RobotWork

func (*RobotWork) String

func (rw *RobotWork) String() string

func (*RobotWork) TickCount

func (rw *RobotWork) TickCount() int

TickCount returns the number of times the function successfully ran

func (*RobotWork) Ticker

func (rw *RobotWork) Ticker() *time.Ticker

Ticker returns the time.Ticker used in an Every so that calling code can sync on the same channel

type RobotWorkRegistry

type RobotWorkRegistry struct {
	sync.RWMutex
	// contains filtered or unexported fields
}

RobotWorkRegistry contains all the work units registered on a Robot

func (*RobotWorkRegistry) Get

func (rwr *RobotWorkRegistry) Get(id uuid.UUID) *RobotWork

Get returns the RobotWork specified by the provided ID. To delete something from the registry, it's necessary to call its context.CancelFunc, which will perform a goroutine-safe delete on the underlying map.

type Robots

type Robots []*Robot

Robots is a collection of Robot

func (*Robots) Each

func (r *Robots) Each(f func(*Robot))

Each enumerates through the Robots and calls specified callback function.

func (*Robots) Len

func (r *Robots) Len() int

Len returns the amount of Robots in the collection.

func (*Robots) Start

func (r *Robots) Start(args ...interface{}) error

Start calls the Start method of each Robot in the collection. We return on first error.

func (*Robots) Stop

func (r *Robots) Stop() error

Stop calls the Stop method of each Robot in the collection. We try to stop all robots and collect the errors.

type SpiOperations

type SpiOperations interface {
	BusOperations
	// ReadCommandData uses the SPI device TX to send/receive data.
	ReadCommandData(command []byte, data []byte) error
	// Close the connection.
	Close() error
}

SpiOperations are the wrappers around the actual functions used by the SPI device interface

type SpiSystemDevicer

type SpiSystemDevicer interface {
	TxRx(tx []byte, rx []byte) error
	// Close the SPI connection.
	Close() error
}

SpiSystemDevicer is the interface to a SPI bus at system level.

Directories

Path Synopsis
api
Package api provides a webserver to interact with your Gobot program over the network.
Package api provides a webserver to interact with your Gobot program over the network.
drivers
aio
Package aio provides Gobot drivers for Analog Input/Output devices.
Package aio provides Gobot drivers for Analog Input/Output devices.
gpio
Package gpio provides Gobot drivers for General Purpose Input/Output devices.
Package gpio provides Gobot drivers for General Purpose Input/Output devices.
i2c
Package i2c provides Gobot drivers for i2c devices.
Package i2c provides Gobot drivers for i2c devices.
spi
Package spi provides Gobot drivers for spi devices.
Package spi provides Gobot drivers for spi devices.
platforms
audio
Package audio is based on aplay audio adaptor written by @colemanserious (https://github.com/colemanserious)
Package audio is based on aplay audio adaptor written by @colemanserious (https://github.com/colemanserious)
beaglebone
Package beaglebone provides the Gobot adaptor for the Beaglebone Black/Green, as well as a separate Adaptor for the PocketBeagle.
Package beaglebone provides the Gobot adaptor for the Beaglebone Black/Green, as well as a separate Adaptor for the PocketBeagle.
ble
Package ble provides the Gobot adaptor for Bluetooth LE.
Package ble provides the Gobot adaptor for Bluetooth LE.
chip
Package chip contains the Gobot adaptor for the CHIP and CHIP Pro
Package chip contains the Gobot adaptor for the CHIP and CHIP Pro
dexter
Package dexter contains Gobot drivers for the Dexter Industries robots
Package dexter contains Gobot drivers for the Dexter Industries robots
dexter/gopigo3
Package gopigo3 is based on https://github.com/DexterInd/GoPiGo3/blob/master/Software/Python/gopigo3.py You will need to run the following commands if using a stock raspbian image before this library will work: sudo curl -kL dexterindustries.com/update_gopigo3 | bash sudo reboot
Package gopigo3 is based on https://github.com/DexterInd/GoPiGo3/blob/master/Software/Python/gopigo3.py You will need to run the following commands if using a stock raspbian image before this library will work: sudo curl -kL dexterindustries.com/update_gopigo3 | bash sudo reboot
digispark
Package digispark provides the Gobot adaptor for the Digispark ATTiny-based USB development board.
Package digispark provides the Gobot adaptor for the Digispark ATTiny-based USB development board.
dji
Package dji contains the Gobot drivers for DJI drones.
Package dji contains the Gobot drivers for DJI drones.
dragonboard
Package dragonboard contains the Gobot adaptor for the DragonBoard 410c
Package dragonboard contains the Gobot adaptor for the DragonBoard 410c
firmata
Package firmata provides the Gobot adaptor for microcontrollers that support the Firmata protocol.
Package firmata provides the Gobot adaptor for microcontrollers that support the Firmata protocol.
firmata/client
Package client provies a client for interacting with microcontrollers using the Firmata protocol https://github.com/firmata/protocol.
Package client provies a client for interacting with microcontrollers using the Firmata protocol https://github.com/firmata/protocol.
holystone
Package holystone contains the Gobot drivers for the Holystone drones.
Package holystone contains the Gobot drivers for the Holystone drones.
holystone/hs200
Package hs200 is the Gobot driver for the Holystone HS200 drone.
Package hs200 is the Gobot driver for the Holystone HS200 drone.
intel-iot
Package inteliot contains Gobot adaptors for the Intel IoT platforms.
Package inteliot contains Gobot adaptors for the Intel IoT platforms.
intel-iot/curie
Package curie contains the Gobot driver for the Intel Curie IMU.
Package curie contains the Gobot driver for the Intel Curie IMU.
intel-iot/edison
Package edison contains the Gobot adaptor for the Intel Edison.
Package edison contains the Gobot adaptor for the Intel Edison.
intel-iot/joule
Package joule contains the Gobot adaptor for the Intel Joule.
Package joule contains the Gobot adaptor for the Intel Joule.
jetson
Package jetson contains the Gobot adaptor for the Jetson Nano.
Package jetson contains the Gobot adaptor for the Jetson Nano.
joystick
Package joystick provides the Gobot adaptor and drivers for game controllers and joysticks.
Package joystick provides the Gobot adaptor and drivers for game controllers and joysticks.
keyboard
Package keyboard contains the Gobot drivers for keyboard support.
Package keyboard contains the Gobot drivers for keyboard support.
leap
Package leap provides the Gobot adaptor and driver for the Leap Motion.
Package leap provides the Gobot adaptor and driver for the Leap Motion.
mavlink
Package mavlink contains the Gobot adaptor and driver for the MAVlink Communication Protocol.
Package mavlink contains the Gobot adaptor and driver for the MAVlink Communication Protocol.
megapi
Package megapi provides the Gobot adaptor for MegaPi.
Package megapi provides the Gobot adaptor for MegaPi.
microbit
Package microbit contains the Gobot drivers for the Microbit.
Package microbit contains the Gobot drivers for the Microbit.
mqtt
Package mqtt provides Gobot adaptor for the mqtt message service.
Package mqtt provides Gobot adaptor for the mqtt message service.
nanopi
Package nanopi contains the Gobot adaptor for the FriendlyARM NanoPi Boards.
Package nanopi contains the Gobot adaptor for the FriendlyARM NanoPi Boards.
nats
Package nats provides Gobot adaptor for the nats message service.
Package nats provides Gobot adaptor for the nats message service.
neurosky
Package neurosky contains the Gobot adaptor and driver for the Neurosky Mindwave Mobile EEG.
Package neurosky contains the Gobot adaptor and driver for the Neurosky Mindwave Mobile EEG.
opencv
Package opencv contains the Gobot drivers for opencv.
Package opencv contains the Gobot drivers for opencv.
parrot
Package parrot contains Gobot adaptors and drivers for the Parrot drones
Package parrot contains Gobot adaptors and drivers for the Parrot drones
parrot/ardrone
Package ardrone provides the Gobot adaptor and driver for the Parrot Ardrone.
Package ardrone provides the Gobot adaptor and driver for the Parrot Ardrone.
parrot/bebop
Package bebop provides the Gobot adaptor and driver for the Parrot Bebop.
Package bebop provides the Gobot adaptor and driver for the Parrot Bebop.
parrot/minidrone
Package minidrone contains the Gobot driver for the Parrot Minidrone.
Package minidrone contains the Gobot driver for the Parrot Minidrone.
particle
Package particle provides the Gobot adaptor for the Particle Photon and Electron.
Package particle provides the Gobot adaptor for the Particle Photon and Electron.
pebble
Package pebble contains the Gobot adaptor and driver for Pebble smart watch.
Package pebble contains the Gobot adaptor and driver for Pebble smart watch.
raspi
Package raspi contains the Gobot adaptor for the Raspberry Pi.
Package raspi contains the Gobot adaptor for the Raspberry Pi.
rockpi
Package rockpi contains the Gobot adaptor for Radxa's Rock Pi Single Board Computers.
Package rockpi contains the Gobot adaptor for Radxa's Rock Pi Single Board Computers.
sphero
Package sphero provides the Gobot adaptor and driver for the Sphero.
Package sphero provides the Gobot adaptor and driver for the Sphero.
sphero/bb8
Package bb8 contains the Gobot driver for the Sphero BB-8.
Package bb8 contains the Gobot driver for the Sphero BB-8.
sphero/ollie
Package ollie contains the Gobot driver for the Sphero Ollie.
Package ollie contains the Gobot driver for the Sphero Ollie.
sphero/sprkplus
Package sprkplus contains the Gobot driver for the Sphero SPRK+.
Package sprkplus contains the Gobot driver for the Sphero SPRK+.
tinkerboard
Package tinkerboard contains the Gobot adaptor for the ASUS Tinker Board.
Package tinkerboard contains the Gobot adaptor for the ASUS Tinker Board.
upboard
Package upboard contains Gobot adaptors for the Upboard SoC boards.
Package upboard contains Gobot adaptors for the Upboard SoC boards.
upboard/up2
Package up2 contains the Gobot adaptor for the Upboard UP2.
Package up2 contains the Gobot adaptor for the Upboard UP2.
Package system provides generic access to Linux gpio, i2c and filesystem.
Package system provides generic access to Linux gpio, i2c and filesystem.

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL