ev3dev

package module
v0.0.0-...-ac0bd47 Latest Latest
Warning

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

Go to latest
Published: Feb 18, 2023 License: BSD-3-Clause Imports: 22 Imported by: 13

README

Gopherbrick

ev3dev is an idiomatic Go interface to an ev3dev device

Build Status Coverage Status GoDoc

The goal is to implement a simple Go style ev3dev API and helpers for common tasks.

github.com/ev3go/ev3dev depends on ev3dev stretch and has been tested on kernel 4.14.61-ev3dev-2.2.2-ev3. For jessie support see the ev3dev-jessie branch.

For device-specific functions see EV3 and BrickPi.

Currently supported:

Low level API
  • Automatic identification of attached devices
  • Buttons /dev/input/by-path/platform-gpio_keys-event
  • Power supply /sys/class/power_supply
  • LED /sys/class/leds
  • LCD /dev/fb0
  • Lego Port /sys/class/lego-port
  • Sensor /sys/class/lego-sensor
  • DC motor /sys/class/dc-motor
  • Linear actuator /sys/class/tacho-motor
  • Servo motor /sys/class/servo-motor
  • Tacho motor /sys/class/tacho-motor
Common tasks
  • Steering helper similar to EV-G steering block

Quick start compiling for a brick

Compiling for a brick can be done on the platform itself if Go is installed there, but it is generally quicker on your computer. This requires that you prefix the go build invocation with GOOS=linux GOARCH=arm GOARM=5. For example, to build the demo program you can do this:

$ GOOS=linux GOARCH=arm GOARM=5 go build github.com/ev3go/ev3dev/examples/demo

This will leave a demo executable (from the name of the package path) in your current directory. You can then copy the executable over to your brick using scp.


LEGO® is a trademark of the LEGO Group of companies which does not sponsor, authorize or endorse this software.

Documentation

Overview

Package ev3dev provides low level access to the ev3dev control and sensor drivers. See documentation at http://www.ev3dev.org/docs/drivers/.

The API provided in the ev3dev package allows fluent chaining of action calls. Methods for each of the device handle types are split into three classes: action, result and constant. Action method calls return the receiver and result method calls return an error value generally with another result. Action methods result in a change of state in the robot while result methods return the requested attribute state of the robot. Constant methods return values that are constant for the device or sensor mode.

To allow fluent call chains, errors are sticky for action methods and are cleared and returned by result methods. In a chain of calls the first error that is caused by an action method prevents execution of all subsequent action method calls, and is returned by the first result method called on the device handle, clearing the error state. Any attribute value returned by a call chain returning a non-nil error is invalid.

To avoid confusion caused by multiple writes to the same underlying device by different handles, only one handle is allowed per physical device.

In most cases, errors returned by functions in the ev3dev package implement the Causer error interface and will be able to print a stack trace if printed with the "+v" fmt verb.

Index

Constants

View Source
const (
	// LEDPath is the path to the ev3 LED file system.
	LEDPath = "/sys/class/leds"

	// ButtonPath is the path to the ev3 button events.
	ButtonPath = "/dev/input/by-path/platform-gpio_keys-event"

	// LegoPortPath is the path to the ev3 lego-port file system.
	LegoPortPath = "/sys/class/lego-port"

	// SensorPath is the path to the ev3 lego-sensor file system.
	SensorPath = "/sys/class/lego-sensor"

	// TachoMotorPath is the path to the ev3 tacho-motor file system.
	TachoMotorPath = "/sys/class/tacho-motor"

	// ServoMotorPath is the path to the ev3 servo-motor file system.
	ServoMotorPath = "/sys/class/servo-motor"

	// DCMotorPath is the path to the ev3 dc-motor file system.
	DCMotorPath = "/sys/class/dc-motor"

	// PowerSupplyPath is the path to the ev3 power supply file system.
	PowerSupplyPath = "/sys/class/power_supply"
)

Variables

This section is empty.

Functions

func AddressOf

func AddressOf(d Device) (string, error)

AddressOf returns the port address of the Device.

func ConnectedTo

func ConnectedTo(p *LegoPort) (string, error)

ConnectedTo returns a description of the device attached to p in the form CONNECTION:PORT:DEVICE where the connection is the underlying transport used by the port and is in {"spi0.1", "serial0-0", "ev3-ports", "evb-ports", "pistorms"} and the port is the name physically printed on the device — with the prefix "in" and "out" for EV3.

func DriverFor

func DriverFor(d Device) (string, error)

DriverFor returns the driver name for the Device.

func FindAfter

func FindAfter(d, dst Device, driver string) error

FindAfter finds the first device after d matching the class of the dst Device with the given driver name, or returns an error. The concrete types of d and dst must match. On return with a nil error, dst is usable as a handle for the device. If d is nil, FindAfter finds the first matching device.

Only ev3dev.Device implementations are supported.

func IsConnected

func IsConnected(d Device) (ok bool, err error)

IsConnected returns whether the Device is connected.

Types

type Button

type Button byte

Button is a set of flags indicating which physical button was pressed.

const (
	Back Button = 1 << iota
	Left
	Middle
	Right
	Up
	Down
)

type ButtonEvent

type ButtonEvent struct {
	Button      Button
	TimeStamp   time.Duration
	Type, Value uint
	Err         error
}

ButtonEvent is a button event, including the time of the event. The Err value reflects any error state arising from detecting the event.

type ButtonPoller

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

ButtonPoller allows polling of the ev3 buttons. The zero value is ready for use.

func (*ButtonPoller) Poll

func (b *ButtonPoller) Poll() (Button, error)

Poll returns a set of Button flags indicating which buttons were pressed when the call was made. Poll does not block.

type ButtonWaiter

type ButtonWaiter struct {
	Events <-chan ButtonEvent
	// contains filtered or unexported fields
}

ButtonWaiter provides a mechanism to block waiting for button events.

func NewButtonWaiter

func NewButtonWaiter() (*ButtonWaiter, error)

NewButtonWaiter returns a ButtonWaiter.

func (*ButtonWaiter) Close

func (b *ButtonWaiter) Close() error

Close closes the backing events source file and the Events channel.

type DCMotor

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

DCMotor represents a handle to a dc-motor.

func DCMotorFor

func DCMotorFor(port, driver string) (*DCMotor, error)

DCMotorFor returns a DCMotor for the given ev3 port name and driver. If the motor driver does not match the driver string, a DCMotor for the port is returned with a DriverMismatch error. If port is empty, the first dc-motor satisfying the driver name is returned.

func (*DCMotor) Command

func (m *DCMotor) Command(comm string) *DCMotor

Command issues a command to the DCMotor.

func (*DCMotor) Commands

func (m *DCMotor) Commands() []string

Commands returns the available commands for the DCMotor.

func (*DCMotor) Driver

func (m *DCMotor) Driver() string

Driver returns the driver used by the DCMotor.

func (*DCMotor) DutyCycle

func (m *DCMotor) DutyCycle() (int, error)

DutyCycle returns the current duty cycle value for the DCMotor.

func (*DCMotor) DutyCycleSetpoint

func (m *DCMotor) DutyCycleSetpoint() (int, error)

DutyCycleSetpoint returns the current duty cycle setpoint value for the DCMotor.

func (*DCMotor) Err

func (m *DCMotor) Err() error

Err returns the error state of the DCMotor and clears it.

func (*DCMotor) Next

func (m *DCMotor) Next() (*DCMotor, error)

Next returns a DCMotor for the next motor with the same device driver as the receiver.

func (*DCMotor) Path

func (*DCMotor) Path() string

Path returns the dc-motor sysfs path.

func (*DCMotor) Polarity

func (m *DCMotor) Polarity() (Polarity, error)

Polarity returns the current polarity of the DCMotor.

func (*DCMotor) RampDownSetpoint

func (m *DCMotor) RampDownSetpoint() (time.Duration, error)

RampDownSetpoint returns the current ramp down setpoint value for the DCMotor.

func (*DCMotor) RampUpSetpoint

func (m *DCMotor) RampUpSetpoint() (time.Duration, error)

RampUpSetpoint returns the current ramp up setpoint value for the DCMotor.

func (*DCMotor) SetDutyCycleSetpoint

func (m *DCMotor) SetDutyCycleSetpoint(sp int) *DCMotor

SetDutyCycleSetpoint sets the duty cycle setpoint value for the DCMotor

func (*DCMotor) SetPolarity

func (m *DCMotor) SetPolarity(p Polarity) *DCMotor

SetPolarity sets the polarity of the DCMotor

func (*DCMotor) SetRampDownSetpoint

func (m *DCMotor) SetRampDownSetpoint(sp time.Duration) *DCMotor

SetRampDownSetpoint sets the ramp down setpoint value for the DCMotor.

func (*DCMotor) SetRampUpSetpoint

func (m *DCMotor) SetRampUpSetpoint(sp time.Duration) *DCMotor

SetRampUpSetpoint sets the ramp up setpoint value for the DCMotor.

func (*DCMotor) SetStopAction

func (m *DCMotor) SetStopAction(action string) *DCMotor

SetStopAction sets the stop action to be used when a stop command is issued to the DCMotor.

func (*DCMotor) SetTimeSetpoint

func (m *DCMotor) SetTimeSetpoint(sp time.Duration) *DCMotor

SetTimeSetpoint sets the time setpoint value for the DCMotor.

func (*DCMotor) State

func (m *DCMotor) State() (MotorState, error)

State returns the current state of the DCMotor.

func (*DCMotor) StopAction

func (m *DCMotor) StopAction() (string, error)

StopAction returns the stop action used when a stop command is issued to the DCMotor.

func (*DCMotor) StopActions

func (m *DCMotor) StopActions() []string

StopActions returns the available stop actions for the DCMotor.

func (*DCMotor) String

func (m *DCMotor) String() string

String satisfies the fmt.Stringer interface.

func (*DCMotor) TimeSetpoint

func (m *DCMotor) TimeSetpoint() (time.Duration, error)

TimeSetpoint returns the current time setpoint value for the DCMotor.

func (*DCMotor) Type

func (*DCMotor) Type() string

Type returns "motor".

func (*DCMotor) Uevent

func (m *DCMotor) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the DCMotor.

type Device

type Device interface {
	// Path returns the sysfs path
	// for the device type.
	Path() string

	// Type returns the type of the
	// device, one of "linear", "motor",
	// "port" or "sensor".
	Type() string

	// Err returns and clears the
	// error state of the Device.
	Err() error

	fmt.Stringer
}

Device is an ev3dev API device.

type DriverMismatch

type DriverMismatch struct {
	// Want is the string describing
	// the requested driver.
	Want string

	// Have is the string describing
	// the driver present on the device.
	Have string
}

DriverMismatch errors are returned when a device is found that does not match the requested driver.

func (DriverMismatch) Error

func (e DriverMismatch) Error() string

type FrameBuffer

type FrameBuffer interface {
	draw.Image

	// Init initializes the frame buffer. If zero
	// is true the frame buffer is zeroed. It is
	// safe to call Init on an already initialized
	// FrameBuffer.
	Init(zero bool) error

	// Close closes the backing file. The FrameBuffer
	// is not usable after a call to Close without a
	// following call to Init.
	Close() error
}

FrameBuffer is the linux frame buffer image interface.

func NewFrameBuffer

func NewFrameBuffer(path string, new func(buf []byte, rect image.Rectangle, stride int) (draw.Image, error), w, h, stride int) FrameBuffer

NewFrameBuffer returns an uninitialized FrameBuffer using the device at path, a frame buffer that is w by h and with the given stride. The new function is a callback that constructs an appropriate draw.Image for the frame buffer bytes.

type LED

type LED struct {
	Name fmt.Stringer
	// contains filtered or unexported fields
}

LED represents a handle to an ev3 LED.

Interaction with shared physical resources is intrinsically subject to race conditions without a transactional model, which is not provided here. If concurrent access to LEDs is needed, the user is required to establish this model.

func (*LED) Brightness

func (l *LED) Brightness() (int, error)

Brightness returns the current brightness value for the LED.

func (*LED) DelayOff

func (l *LED) DelayOff() (time.Duration, error)

DelayOff returns the duration for which the LED is off when using the timer trigger.

func (*LED) DelayOn

func (l *LED) DelayOn() (time.Duration, error)

DelayOn returns the duration for which the LED is on when using the timer trigger.

func (*LED) Err

func (l *LED) Err() error

Err returns the error state of the LED and clears it.

func (*LED) MaxBrightness

func (l *LED) MaxBrightness() (int, error)

MaxBrightness returns the maximum brightness value for the LED.

func (*LED) Path

func (l *LED) Path() string

Path returns the LED sysfs path.

func (*LED) SetBrightness

func (l *LED) SetBrightness(bright int) *LED

SetBrightness sets the brightness of the LED.

func (*LED) SetDelayOff

func (l *LED) SetDelayOff(d time.Duration) *LED

SetDelayOff sets the duration for which the LED is off when using the timer trigger.

func (*LED) SetDelayOn

func (l *LED) SetDelayOn(d time.Duration) *LED

SetDelayOn sets the duration for which the LED is on when using the timer trigger.

func (*LED) SetTrigger

func (l *LED) SetTrigger(trig string) *LED

SetTrigger sets the trigger for the LED.

func (*LED) String

func (l *LED) String() string

String satisfies the fmt.Stringer interface.

func (*LED) Trigger

func (l *LED) Trigger() (current string, available []string, err error)

Trigger returns the current and available triggers for the LED.

func (*LED) Uevent

func (l *LED) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the LED.

type LegoPort

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

LegoPort represents a handle to a lego-port.

func LegoPortFor

func LegoPortFor(port, driver string) (*LegoPort, error)

LegoPortFor returns a LegoPort for the given ev3 port name and driver. If the lego-port driver does not match the driver string, a LegoPort for the port is returned with a DriverMismatch error. If port is empty, the first port satisfying the driver name is returned.

func (*LegoPort) Driver

func (p *LegoPort) Driver() string

Driver returns the driver used by the LegoPort.

func (*LegoPort) Err

func (p *LegoPort) Err() error

Err returns the error state of the LegoPort and clears it.

func (*LegoPort) Mode

func (p *LegoPort) Mode() string

Mode returns the currently selected mode of the LegoPort.

func (*LegoPort) Modes

func (p *LegoPort) Modes() []string

Modes returns the available modes for the LegoPort.

func (*LegoPort) Next

func (p *LegoPort) Next() (*LegoPort, error)

Next returns a LegoPort for the next port with the same device driver as the receiver.

func (*LegoPort) Path

func (*LegoPort) Path() string

Path returns the lego-port sysfs path.

func (*LegoPort) SetDevice

func (p *LegoPort) SetDevice(d string) *LegoPort

SetDevice sets the device of the LegoPort.

func (*LegoPort) SetMode

func (p *LegoPort) SetMode(m string) *LegoPort

SetMode sets the mode of the LegoPort.

func (*LegoPort) Status

func (p *LegoPort) Status() (string, error)

Status returns the current status of the LegoPort.

func (*LegoPort) String

func (p *LegoPort) String() string

String satisfies the fmt.Stringer interface.

func (*LegoPort) Type

func (*LegoPort) Type() string

Type returns "port".

func (*LegoPort) Uevent

func (p *LegoPort) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the LegoPort.

type LinearActuator

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

LinearActuator represents a handle to a linear actuator tacho-motor.

func LinearActuatorFor

func LinearActuatorFor(port, driver string) (*LinearActuator, error)

LinearActuatorFor returns a LinearActuator for the given ev3 port name and driver. If the motor driver does not match the driver string, a LinearActuator for the port is returned with a DriverMismatch error. If port is empty, the first tacho-motor satisfying the driver name is returned.

func (*LinearActuator) Command

func (m *LinearActuator) Command(comm string) *LinearActuator

Command issues a command to the LinearActuator.

func (*LinearActuator) Commands

func (m *LinearActuator) Commands() []string

Commands returns the available commands for the LinearActuator.

func (*LinearActuator) CountPerMeter

func (m *LinearActuator) CountPerMeter() int

CountPerMeter returns the number of tacho counts in one meter of travel of the motor.

func (*LinearActuator) Driver

func (m *LinearActuator) Driver() string

Driver returns the driver used by the LinearActuator.

func (*LinearActuator) DutyCycle

func (m *LinearActuator) DutyCycle() (int, error)

DutyCycle returns the current duty cycle value for the LinearActuator.

func (*LinearActuator) DutyCycleSetpoint

func (m *LinearActuator) DutyCycleSetpoint() (int, error)

DutyCycleSetpoint returns the current duty cycle setpoint value for the LinearActuator.

func (*LinearActuator) Err

func (m *LinearActuator) Err() error

Err returns the error state of the LinearActuator and clears it.

func (*LinearActuator) FullTravelCount

func (m *LinearActuator) FullTravelCount() int

FullTravelCount returns the the number of tacho counts in the full travel of the motor.

func (*LinearActuator) HoldPIDKd

func (m *LinearActuator) HoldPIDKd() (int, error)

HoldPIDKd returns the derivative constant for the position PID for the LinearActuator.

func (*LinearActuator) HoldPIDKi

func (m *LinearActuator) HoldPIDKi() (int, error)

HoldPIDKi returns the integral constant for the position PID for the LinearActuator.

func (*LinearActuator) HoldPIDKp

func (m *LinearActuator) HoldPIDKp() (int, error)

HoldPIDKp returns the proportional constant for the position PID for the LinearActuator.

func (*LinearActuator) MaxSpeed

func (m *LinearActuator) MaxSpeed() int

MaxSpeed returns the maximum value that is accepted by SpeedSetpoint.

func (*LinearActuator) Next

func (m *LinearActuator) Next() (*LinearActuator, error)

Next returns a LinearActuator for the next motor with the same device driver as the receiver.

func (*LinearActuator) Path

func (*LinearActuator) Path() string

Path returns the tacho-motor sysfs path.

func (*LinearActuator) Polarity

func (m *LinearActuator) Polarity() (Polarity, error)

Polarity returns the current polarity of the LinearActuator.

func (*LinearActuator) Position

func (m *LinearActuator) Position() (int, error)

Position returns the current position value for the LinearActuator.

func (*LinearActuator) PositionSetpoint

func (m *LinearActuator) PositionSetpoint() (int, error)

PositionSetpoint returns the current position setpoint value for the LinearActuator.

func (*LinearActuator) RampDownSetpoint

func (m *LinearActuator) RampDownSetpoint() (time.Duration, error)

RampDownSetpoint returns the current ramp down setpoint value for the LinearActuator.

func (*LinearActuator) RampUpSetpoint

func (m *LinearActuator) RampUpSetpoint() (time.Duration, error)

RampUpSetpoint returns the current ramp up setpoint value for the LinearActuator.

func (*LinearActuator) SetDutyCycleSetpoint

func (m *LinearActuator) SetDutyCycleSetpoint(sp int) *LinearActuator

SetDutyCycleSetpoint sets the duty cycle setpoint value for the LinearActuator

func (*LinearActuator) SetHoldPIDKd

func (m *LinearActuator) SetHoldPIDKd(k int) *LinearActuator

SetHoldPIDKd sets the derivative constant for the position PID for the LinearActuator.

func (*LinearActuator) SetHoldPIDKi

func (m *LinearActuator) SetHoldPIDKi(k int) *LinearActuator

SetHoldPIDKi sets the integral constant for the position PID for the LinearActuator.

func (*LinearActuator) SetHoldPIDKp

func (m *LinearActuator) SetHoldPIDKp(k int) *LinearActuator

SetHoldPIDKp sets the proportional constant for the position PID for the LinearActuator.

func (*LinearActuator) SetPolarity

func (m *LinearActuator) SetPolarity(p Polarity) *LinearActuator

SetPolarity sets the polarity of the LinearActuator

func (*LinearActuator) SetPosition

func (m *LinearActuator) SetPosition(pos int) *LinearActuator

SetPosition sets the position value for the LinearActuator.

func (*LinearActuator) SetPositionSetpoint

func (m *LinearActuator) SetPositionSetpoint(sp int) *LinearActuator

SetPositionSetpoint sets the position setpoint value for the LinearActuator.

func (*LinearActuator) SetRampDownSetpoint

func (m *LinearActuator) SetRampDownSetpoint(sp time.Duration) *LinearActuator

SetRampDownSetpoint sets the ramp down setpoint value for the LinearActuator.

func (*LinearActuator) SetRampUpSetpoint

func (m *LinearActuator) SetRampUpSetpoint(sp time.Duration) *LinearActuator

SetRampUpSetpoint sets the ramp up setpoint value for the LinearActuator.

func (*LinearActuator) SetSpeedPIDKd

func (m *LinearActuator) SetSpeedPIDKd(sp int) *LinearActuator

SetSpeedPIDKd sets the derivative constant for the speed regulation PID for the LinearActuator.

func (*LinearActuator) SetSpeedPIDKi

func (m *LinearActuator) SetSpeedPIDKi(sp int) *LinearActuator

SetSpeedPIDKi sets the integral constant for the speed regulation PID for the LinearActuator.

func (*LinearActuator) SetSpeedPIDKp

func (m *LinearActuator) SetSpeedPIDKp(sp int) *LinearActuator

SetSpeedPIDKp sets the proportional constant for the speed regulation PID for the LinearActuator.

func (*LinearActuator) SetSpeedSetpoint

func (m *LinearActuator) SetSpeedSetpoint(sp int) *LinearActuator

SetSpeedSetpoint sets the speed setpoint value for the LinearActuator.

func (*LinearActuator) SetStopAction

func (m *LinearActuator) SetStopAction(action string) *LinearActuator

SetStopAction sets the stop action to be used when a stop command is issued to the LinearActuator.

func (*LinearActuator) SetTimeSetpoint

func (m *LinearActuator) SetTimeSetpoint(sp time.Duration) *LinearActuator

SetTimeSetpoint sets the time setpoint value for the LinearActuator.

func (*LinearActuator) Speed

func (m *LinearActuator) Speed() (int, error)

Speed returns the current speed of the LinearActuator.

func (*LinearActuator) SpeedPIDKd

func (m *LinearActuator) SpeedPIDKd() (int, error)

SpeedPIDKd returns the derivative constant for the speed regulation PID for the LinearActuator.

func (*LinearActuator) SpeedPIDKi

func (m *LinearActuator) SpeedPIDKi() (int, error)

SpeedPIDKi returns the integral constant for the speed regulation PID for the LinearActuator.

func (*LinearActuator) SpeedPIDKp

func (m *LinearActuator) SpeedPIDKp() (int, error)

SpeedPIDKp returns the proportional constant for the speed regulation PID for the LinearActuator.

func (*LinearActuator) SpeedSetpoint

func (m *LinearActuator) SpeedSetpoint() (int, error)

SpeedSetpoint returns the current speed setpoint value for the LinearActuator.

func (*LinearActuator) State

func (m *LinearActuator) State() (MotorState, error)

State returns the current state of the LinearActuator.

func (*LinearActuator) StopAction

func (m *LinearActuator) StopAction() (string, error)

StopAction returns the stop action used when a stop command is issued to the LinearActuator.

func (*LinearActuator) StopActions

func (m *LinearActuator) StopActions() []string

StopActions returns the available stop actions for the LinearActuator.

func (*LinearActuator) String

func (m *LinearActuator) String() string

String satisfies the fmt.Stringer interface.

func (*LinearActuator) TimeSetpoint

func (m *LinearActuator) TimeSetpoint() (time.Duration, error)

TimeSetpoint returns the current time setpoint value for the LinearActuator.

func (*LinearActuator) Type

func (*LinearActuator) Type() string

Type returns "linear".

func (*LinearActuator) Uevent

func (m *LinearActuator) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the LinearActuator.

type MotorState

type MotorState uint

MotorState is a flag set representing the state of a TachoMotor.

const (
	Running MotorState = 1 << iota
	Ramping
	Holding
	Overloaded
	Stalled
)

func Wait

func Wait(d StaterDevice, mask, want, not MotorState, any bool, timeout time.Duration) (stat MotorState, ok bool, err error)

Wait blocks until the wanted motor state under the motor state mask is reached, or the timeout is reached. If timeout is negative Wait will wait indefinitely for the wanted motor state has been reached. The last unmasked motor state is returned unless the timeout was reached before the motor state was read. When the any parameter is false, Wait will return ok as true if

(state&mask)^not == want|not

and when any is true Wait return false if

(state&mask)^not != 0 && state&mask&not == 0 .

Otherwise ok will return false indicating that the returned state did not match the request. Wait will not set the error state of the StaterDevice, but will clear and return it if it is not nil.

func (MotorState) String

func (f MotorState) String() string

String satisfies the fmt.Stringer interface.

type Polarity

type Polarity string

Polarity represent motor polarity states.

const (
	Normal   Polarity = "normal"
	Inversed Polarity = "inversed"
)

type PowerSupply

type PowerSupply string

PowerSupply represents a handle to a the ev3 power supply controller. The zero value is usable, reading from the first available device in the power supply file system, falling back to the legoev3-battery driver. Using another string value will read from the device of that name.

func (PowerSupply) Current

func (p PowerSupply) Current() (float64, error)

Current returns the current drawn from the power supply in milliamps.

func (PowerSupply) Path

func (p PowerSupply) Path() string

Path returns the power-supply sysfs path.

func (PowerSupply) String

func (p PowerSupply) String() string

String satisfies the fmt.Stringer interface.

String scans the PowerSupplyPath directory if p is the zero value. To avoid this the user should set p to the returned value on the first use.

func (PowerSupply) Technology

func (p PowerSupply) Technology() (string, error)

Technology returns the battery technology of the power supply.

func (PowerSupply) Type

func (p PowerSupply) Type() (string, error)

Type returns the battery type of the power supply.

func (PowerSupply) Uevent

func (p PowerSupply) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the power supply.

func (PowerSupply) Voltage

func (p PowerSupply) Voltage() (float64, error)

Voltage returns voltage measured from the power supply in volts.

func (PowerSupply) VoltageMax

func (p PowerSupply) VoltageMax() (float64, error)

VoltageMax returns the maximum design voltage for the power supply in volts.

func (PowerSupply) VoltageMin

func (p PowerSupply) VoltageMin() (float64, error)

VoltageMin returns the minimum design voltage for the power supply in volts.

type Sensor

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

Sensor represents a handle to a lego-sensor.

func SensorFor

func SensorFor(port, driver string) (*Sensor, error)

SensorFor returns a Sensor for the given ev3 port name and driver. If the sensor driver does not match the driver string, a Sensor for the port is returned with a DriverMismatch error. If port is empty, the first sensor satisfying the driver name is returned.

func (*Sensor) BinData

func (s *Sensor) BinData() ([]byte, error)

BinData returns the unscaled raw values from the Sensor.

func (*Sensor) BinDataFormat

func (s *Sensor) BinDataFormat() string

BinDataFormat returns the format of the values returned by BinData for the current mode.

The returned values should be interpretted according to:

u8: Unsigned 8-bit integer (byte)
s8: Signed 8-bit integer (sbyte)
u16: Unsigned 16-bit integer (ushort)
s16: Signed 16-bit integer (short)
s16_be: Signed 16-bit integer, big endian
s32: Signed 32-bit integer (int)
s32_be: Signed 32-bit integer, big endian
float: IEEE 754 32-bit floating point (float)

func (*Sensor) Command

func (s *Sensor) Command(comm string) *Sensor

Command issues a command to the Sensor.

func (*Sensor) Commands

func (s *Sensor) Commands() []string

Commands returns the available commands for the Sensor.

func (*Sensor) Decimals

func (s *Sensor) Decimals() int

Decimals returns the number of decimal places for the values in the attributes of the current mode.

func (*Sensor) Direct

func (s *Sensor) Direct(flag int) (*os.File, error)

Direct returns a file that can be used to directly communication with the sensor for using advanced features that are not otherwise available through the lego-sensor class. It is the responsibility of the user to provide the correct file operation flags, and to close the file after use.

func (*Sensor) Driver

func (s *Sensor) Driver() string

Driver returns the driver used by the Sensor.

func (*Sensor) Err

func (s *Sensor) Err() error

Err returns the error state of the Sensor and clears it.

func (*Sensor) FirmwareVersion

func (s *Sensor) FirmwareVersion() string

FirmwareVersion returns the firmware version of the Sensor.

func (*Sensor) Mode

func (s *Sensor) Mode() (string, error)

Mode returns the currently selected mode of the Sensor.

func (*Sensor) Modes

func (s *Sensor) Modes() []string

Modes returns the available modes for the Sensor.

func (*Sensor) Next

func (s *Sensor) Next() (*Sensor, error)

Next returns a Sensor for the next sensor with the same device driver as the receiver.

func (*Sensor) NumValues

func (s *Sensor) NumValues() int

NumValues returns number of values available from the Sensor.

func (*Sensor) Path

func (*Sensor) Path() string

Path returns the lego-sensor sysfs path.

func (*Sensor) PollRate

func (s *Sensor) PollRate() (time.Duration, error)

PollRate returns the current polling rate value for the Sensor.

func (*Sensor) SetMode

func (s *Sensor) SetMode(m string) *Sensor

SetMode sets the mode of the Sensor. Calling SetMode invalidates and refreshes cached values for BinDataFormat, Decimals, Mode, NumValues and Units.

func (*Sensor) SetPollRate

func (s *Sensor) SetPollRate(d time.Duration) *Sensor

SetPollRate sets the polling rate value for the Sensor.

func (*Sensor) String

func (s *Sensor) String() string

String satisfies the fmt.Stringer interface.

func (*Sensor) TextValues

func (s *Sensor) TextValues() ([]string, error)

TextValues returns slice of strings string representing sensor-specific text values.

func (*Sensor) Type

func (*Sensor) Type() string

Type returns "sensor".

func (*Sensor) Uevent

func (s *Sensor) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the Sensor.

func (*Sensor) Units

func (s *Sensor) Units() string

Units returns the units of the measured value for the current mode for the Sensor.

func (*Sensor) Value

func (s *Sensor) Value(n int) (string, error)

Value returns tthe value or values measured by the Sensor. Value will return and error if n is greater than or equal to the value returned by NumValues.

type ServoMotor

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

ServoMotor represents a handle to a servo-motor.

func ServoMotorFor

func ServoMotorFor(port, driver string) (*ServoMotor, error)

ServoMotorFor returns a ServoMotor for the given ev3 port name and driver. If the motor driver does not match the driver string, a ServoMotor for the port is returned with a DriverMismatch error. If port is empty, the first servo-motor satisfying the driver name is returned.

func (*ServoMotor) Command

func (m *ServoMotor) Command(comm string) *ServoMotor

Command issues a command to the ServoMotor.

func (*ServoMotor) Commands

func (m *ServoMotor) Commands() []string

Commands returns the available commands for the ServoMotor.

func (*ServoMotor) Driver

func (p *ServoMotor) Driver() string

Driver returns the driver used by the ServoMotor.

func (*ServoMotor) Err

func (m *ServoMotor) Err() error

Err returns the error state of the ServoMotor and clears it.

func (*ServoMotor) MaxPulseSetpoint

func (m *ServoMotor) MaxPulseSetpoint() (time.Duration, error)

MaxPulseSetpoint returns the current max pulse setpoint value for the ServoMotor.

func (*ServoMotor) MidPulseSetpoint

func (m *ServoMotor) MidPulseSetpoint() (time.Duration, error)

MidPulseSetpoint returns the current mid pulse setpoint value for the ServoMotor.

func (*ServoMotor) MinPulseSetpoint

func (m *ServoMotor) MinPulseSetpoint() (time.Duration, error)

MinPulseSetpoint returns the current min pulse setpoint value for the ServoMotor.

func (*ServoMotor) Next

func (m *ServoMotor) Next() (*ServoMotor, error)

Next returns a ServoMotor for the next motor with the same device driver as the receiver.

func (*ServoMotor) Path

func (*ServoMotor) Path() string

Path returns the servo-motor sysfs path.

func (*ServoMotor) Polarity

func (m *ServoMotor) Polarity() (Polarity, error)

Polarity returns the current polarity of the ServoMotor.

func (*ServoMotor) PositionSetpoint

func (m *ServoMotor) PositionSetpoint() (int, error)

PositionSetpoint returns the current position setpoint value for the ServoMotor.

func (*ServoMotor) RateSetpoint

func (m *ServoMotor) RateSetpoint() (time.Duration, error)

RateSetpoint returns the current rate setpoint value for the ServoMotor.

func (*ServoMotor) SetMaxPulseSetpoint

func (m *ServoMotor) SetMaxPulseSetpoint(sp time.Duration) *ServoMotor

SetMaxPulseSetpoint sets the max pulse setpoint value for the ServoMotor

func (*ServoMotor) SetMidPulseSetpoint

func (m *ServoMotor) SetMidPulseSetpoint(sp time.Duration) *ServoMotor

SetMidPulseSetpoint sets the mid pulse setpoint value for the ServoMotor

func (*ServoMotor) SetMinPulseSetpoint

func (m *ServoMotor) SetMinPulseSetpoint(sp time.Duration) *ServoMotor

SetMinPulseSetpoint sets the min pulse setpoint value for the ServoMotor

func (*ServoMotor) SetPolarity

func (m *ServoMotor) SetPolarity(p Polarity) *ServoMotor

SetPolarity sets the polarity of the ServoMotor

func (*ServoMotor) SetPositionSetpoint

func (m *ServoMotor) SetPositionSetpoint(sp int) *ServoMotor

SetPositionSetpoint sets the position value for the ServoMotor.

func (*ServoMotor) SetRateSetpoint

func (m *ServoMotor) SetRateSetpoint(sp time.Duration) *ServoMotor

SetRateSetpoint sets the rate setpoint value for the ServoMotor.

func (*ServoMotor) State

func (m *ServoMotor) State() (MotorState, error)

State returns the current state of the ServoMotor.

func (*ServoMotor) String

func (m *ServoMotor) String() string

String satisfies the fmt.Stringer interface.

func (*ServoMotor) Type

func (*ServoMotor) Type() string

Type returns "motor".

func (*ServoMotor) Uevent

func (m *ServoMotor) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the ServoMotor.

type Speaker

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

Speaker is an evdev sound device.

func NewSpeaker

func NewSpeaker(path string) *Speaker

NewSpeaker returns a new Speaker based on the given evdev snd device path.

func (*Speaker) Close

func (s *Speaker) Close() error

Close closes the Speaker. After return, the Speaker may not be used unless Init is called again.

func (*Speaker) Init

func (s *Speaker) Init() error

Init prepares a Speaker for use.

func (*Speaker) Tone

func (s *Speaker) Tone(freq uint32) error

Tone plays a tone at the specified frequency from the ev3 speaker. If freq is zero, playing is stopped.

type StaterDevice

type StaterDevice interface {
	Device
	State() (MotorState, error)
}

StaterDevice is a device that can return a motor state.

type TachoMotor

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

TachoMotor represents a handle to a tacho-motor.

func TachoMotorFor

func TachoMotorFor(port, driver string) (*TachoMotor, error)

TachoMotorFor returns a TachoMotor for the given ev3 port name and driver. If the motor driver does not match the driver string, a TechoMotor for the port is returned with a DriverMismatch error. If port is empty, the first tacho-motor satisfying the driver name is returned.

func (*TachoMotor) Command

func (m *TachoMotor) Command(comm string) *TachoMotor

Command issues a command to the TachoMotor.

func (*TachoMotor) Commands

func (m *TachoMotor) Commands() []string

Commands returns the available commands for the TachoMotor.

func (*TachoMotor) CountPerRot

func (m *TachoMotor) CountPerRot() int

CountPerRot returns the number of tacho counts in one rotation of the motor.

func (*TachoMotor) Driver

func (m *TachoMotor) Driver() string

Driver returns the driver used by the TachoMotor.

func (*TachoMotor) DutyCycle

func (m *TachoMotor) DutyCycle() (int, error)

DutyCycle returns the current duty cycle value for the TachoMotor.

func (*TachoMotor) DutyCycleSetpoint

func (m *TachoMotor) DutyCycleSetpoint() (int, error)

DutyCycleSetpoint returns the current duty cycle setpoint value for the TachoMotor.

func (*TachoMotor) Err

func (m *TachoMotor) Err() error

Err returns the error state of the TachoMotor and clears it.

func (*TachoMotor) HoldPIDKd

func (m *TachoMotor) HoldPIDKd() (int, error)

HoldPIDKd returns the derivative constant for the position PID for the TachoMotor.

func (*TachoMotor) HoldPIDKi

func (m *TachoMotor) HoldPIDKi() (int, error)

HoldPIDKi returns the integral constant for the position PID for the TachoMotor.

func (*TachoMotor) HoldPIDKp

func (m *TachoMotor) HoldPIDKp() (int, error)

HoldPIDKp returns the proportional constant for the position PID for the TachoMotor.

func (*TachoMotor) MaxSpeed

func (m *TachoMotor) MaxSpeed() int

MaxSpeed returns the maximum value that is accepted by SpeedSetpoint.

func (*TachoMotor) Next

func (m *TachoMotor) Next() (*TachoMotor, error)

Next returns a TachoMotor for the next motor with the same device driver as the receiver.

func (*TachoMotor) Path

func (*TachoMotor) Path() string

Path returns the tacho-motor sysfs path.

func (*TachoMotor) Polarity

func (m *TachoMotor) Polarity() (Polarity, error)

Polarity returns the current polarity of the TachoMotor.

func (*TachoMotor) Position

func (m *TachoMotor) Position() (int, error)

Position returns the current position value for the TachoMotor.

func (*TachoMotor) PositionSetpoint

func (m *TachoMotor) PositionSetpoint() (int, error)

PositionSetpoint returns the current position setpoint value for the TachoMotor.

func (*TachoMotor) RampDownSetpoint

func (m *TachoMotor) RampDownSetpoint() (time.Duration, error)

RampDownSetpoint returns the current ramp down setpoint value for the TachoMotor.

func (*TachoMotor) RampUpSetpoint

func (m *TachoMotor) RampUpSetpoint() (time.Duration, error)

RampUpSetpoint returns the current ramp up setpoint value for the TachoMotor.

func (*TachoMotor) SetDutyCycleSetpoint

func (m *TachoMotor) SetDutyCycleSetpoint(sp int) *TachoMotor

SetDutyCycleSetpoint sets the duty cycle setpoint value for the TachoMotor

func (*TachoMotor) SetHoldPIDKd

func (m *TachoMotor) SetHoldPIDKd(k int) *TachoMotor

SetHoldPIDKd sets the derivative constant for the position PID for the TachoMotor.

func (*TachoMotor) SetHoldPIDKi

func (m *TachoMotor) SetHoldPIDKi(k int) *TachoMotor

SetHoldPIDKi sets the integral constant for the position PID for the TachoMotor.

func (*TachoMotor) SetHoldPIDKp

func (m *TachoMotor) SetHoldPIDKp(k int) *TachoMotor

SetHoldPIDKp sets the proportional constant for the position PID for the TachoMotor.

func (*TachoMotor) SetPolarity

func (m *TachoMotor) SetPolarity(p Polarity) *TachoMotor

SetPolarity sets the polarity of the TachoMotor

func (*TachoMotor) SetPosition

func (m *TachoMotor) SetPosition(pos int) *TachoMotor

SetPosition sets the position value for the TachoMotor.

func (*TachoMotor) SetPositionSetpoint

func (m *TachoMotor) SetPositionSetpoint(sp int) *TachoMotor

SetPositionSetpoint sets the position setpoint value for the TachoMotor.

func (*TachoMotor) SetRampDownSetpoint

func (m *TachoMotor) SetRampDownSetpoint(sp time.Duration) *TachoMotor

SetRampDownSetpoint sets the ramp down setpoint value for the TachoMotor.

func (*TachoMotor) SetRampUpSetpoint

func (m *TachoMotor) SetRampUpSetpoint(sp time.Duration) *TachoMotor

SetRampUpSetpoint sets the ramp up setpoint value for the TachoMotor.

func (*TachoMotor) SetSpeedPIDKd

func (m *TachoMotor) SetSpeedPIDKd(k int) *TachoMotor

SetSpeedPIDKd sets the derivative constant for the speed regulation PID for the TachoMotor.

func (*TachoMotor) SetSpeedPIDKi

func (m *TachoMotor) SetSpeedPIDKi(k int) *TachoMotor

SetSpeedPIDKi sets the integral constant for the speed regulation PID for the TachoMotor.

func (*TachoMotor) SetSpeedPIDKp

func (m *TachoMotor) SetSpeedPIDKp(k int) *TachoMotor

SetSpeedPIDKp sets the proportional constant for the speed regulation PID for the TachoMotor.

func (*TachoMotor) SetSpeedSetpoint

func (m *TachoMotor) SetSpeedSetpoint(sp int) *TachoMotor

SetSpeedSetpoint sets the speed setpoint value for the TachoMotor.

func (*TachoMotor) SetStopAction

func (m *TachoMotor) SetStopAction(action string) *TachoMotor

SetStopAction sets the stop action to be used when a stop command is issued to the TachoMotor.

func (*TachoMotor) SetTimeSetpoint

func (m *TachoMotor) SetTimeSetpoint(sp time.Duration) *TachoMotor

SetTimeSetpoint sets the time setpoint value for the TachoMotor.

func (*TachoMotor) Speed

func (m *TachoMotor) Speed() (int, error)

Speed returns the current speed of the TachoMotor.

func (*TachoMotor) SpeedPIDKd

func (m *TachoMotor) SpeedPIDKd() (int, error)

SpeedPIDKd returns the derivative constant for the speed regulation PID for the TachoMotor.

func (*TachoMotor) SpeedPIDKi

func (m *TachoMotor) SpeedPIDKi() (int, error)

SpeedPIDKi returns the integral constant for the speed regulation PID for the TachoMotor.

func (*TachoMotor) SpeedPIDKp

func (m *TachoMotor) SpeedPIDKp() (int, error)

SpeedPIDKp returns the proportional constant for the speed regulation PID for the TachoMotor.

func (*TachoMotor) SpeedSetpoint

func (m *TachoMotor) SpeedSetpoint() (int, error)

SpeedSetpoint returns the current speed setpoint value for the TachoMotor.

func (*TachoMotor) State

func (m *TachoMotor) State() (MotorState, error)

State returns the current state of the TachoMotor.

func (*TachoMotor) StopAction

func (m *TachoMotor) StopAction() (string, error)

StopAction returns the stop action used when a stop command is issued to the TachoMotor.

func (*TachoMotor) StopActions

func (m *TachoMotor) StopActions() []string

StopActions returns the available stop actions for the TachoMotor.

func (*TachoMotor) String

func (m *TachoMotor) String() string

String satisfies the fmt.Stringer interface.

func (*TachoMotor) TimeSetpoint

func (m *TachoMotor) TimeSetpoint() (time.Duration, error)

TimeSetpoint returns the current time setpoint value for the TachoMotor.

func (*TachoMotor) Type

func (*TachoMotor) Type() string

Type returns "motor".

func (*TachoMotor) Uevent

func (m *TachoMotor) Uevent() (map[string]string, error)

Uevent returns the current uevent state for the TachoMotor.

type ValidDurationRanger

type ValidDurationRanger interface {
	// DurationRange returns the invalid value
	// and the range of valid values.
	DurationRange() (value, min, max time.Duration)
}

ValidDurationRanger is an error caused by an invalid ranged time.Duration value.

type ValidRanger

type ValidRanger interface {
	// Range returns the invalid value
	// and the range of valid values.
	Range() (value, min, max int)
}

ValidRanger is an error caused by an invalid ranged integer value.

type ValidValuer

type ValidValuer interface {
	// Values returns the invalid value
	// and a slice of valid values.
	Values() (value string, valid []string)
}

ValidValuer is an error caused by an invalid discrete value.

Directories

Path Synopsis
examples
demo
demo is a reimplementation of the Demo program loaded on new ev3 bricks, without sound.
demo is a reimplementation of the Demo program loaded on new ev3 bricks, without sound.
find
find demonstrates finding the first available sensor for a driver name.
find demonstrates finding the first available sensor for a driver name.
findafter
findafter demonstrates finding the two first available large motors.
findafter demonstrates finding the two first available large motors.
gps
gps demonstrates use of the Dexter Industries dGPS device.
gps demonstrates use of the Dexter Industries dGPS device.
poll
keys demonstrates key polling.
keys demonstrates key polling.
power
power demonstrates using the PowerSupply type.
power demonstrates using the PowerSupply type.
speaker
speaker demonstrates use of the ev3dev speaker.
speaker demonstrates use of the ev3dev speaker.
stopall
stopall stops all motors.
stopall stops all motors.
waitkeys
waitkeys demonstrates key waiting.
waitkeys demonstrates key waiting.
znap
znap is a reimplementation of the control program for the Znap robot with the modification that the ultrasonic sensor is autodetected so that it works with the instructions as printed and with models built to work with the control program provided in the Mindstorms software.
znap is a reimplementation of the control program for the Znap robot with the modification that the ultrasonic sensor is autodetected so that it works with the instructions as printed and with models built to work with the control program provided in the Mindstorms software.
Package fb provides frame buffer image handling.
Package fb provides frame buffer image handling.
Package motorutil provides utilities for motor handling.
Package motorutil provides utilities for motor handling.

Jump to

Keyboard shortcuts

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