roomba

package module
v0.0.0-...-9743d78 Latest Latest
Warning

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

Go to latest
Published: Oct 7, 2017 License: MIT Imports: 8 Imported by: 13

README

Go-Roomba

A go library for interacting with iRobot Roomba or Create robots following the Open Interface (OI) specification.

Build Status Coverage Status

Details

The code of the library is remotely inspired by pyrobot library by damonkohler@gmail.com (Damon Kohler)

I'm still not sure on how to package go libraries, but

go get github.com/xa4a/go-roomba/go-roomba-test
$GOPATH/bin/go-roomba-test  # -port=/dev/roomba_serial_port

Should output:

2012/10/29 16:41:40 Failed to open serial port: /dev/cu.usbserial-FTTL3AW0
2012/10/29 16:41:40 Making roomba failed
exit status 1

And if you have Roomba connected to the specified port (/dev/cu.usbserial-FTTL3AW0 above) it may move forward a bit.

Documentation

Overview

Package roomba defines and implements the interface for interacting with iRobot Roomba Open Interface robots.

Index

Constants

This section is empty.

Variables

View Source
var OpCodes = constants.OpCodes

Functions

func Pack

func Pack(data []interface{}) []byte

Packs the given data as big endian bytes.

Types

type Roomba

type Roomba struct {
	PortName     string
	S            io.ReadWriter
	StreamPaused chan bool
}

func MakeRoomba

func MakeRoomba(port_name string) (*Roomba, error)

MakeRoomba initializes a new Roomba structure and sets up a serial port. By default, Roomba communicates at 115200 baud.

func (*Roomba) Clean

func (this *Roomba) Clean() error

Clean command starts the default cleaning mode.

func (*Roomba) Control

func (this *Roomba) Control() error

Control command's effect and usage are identical to the Safe command.

func (*Roomba) DirectDrive

func (this *Roomba) DirectDrive(right, left int16) error

DirectDrive command lets you control the forward and backward motion of Roomba’s drive wheels independently. It takes two 16-bit signed values. The first specifies the velocity of the right wheel in millimeters per second (mm/s), The next one specifies the velocity of the left wheel A positive velocity makes that wheel drive forward, while a negative velocity makes it drive backward. Right wheel velocity (-500 – 500 mm/s). Left wheel velocity (-500 – 500 mm/s).

func (*Roomba) Drive

func (this *Roomba) Drive(velocity, radius int16) error

Drive command controls Roomba’s drive wheels. It takes two 16-bit signed values. The first one specifies the average velocity of the drive wheels in millimeters per second (mm/s). The next one specifies the radius in millimeters at which Roomba will turn. The longer radii make Roomba drive straighter, while the shorter radii make Roomba turn more. The radius is measured from the center of the turning circle to the center of Roomba. A Drive command with a positive velocity and a positive radius makes Roomba drive forward while turning toward the left. A negative radius makes Roomba turn toward the right. Special cases for the radius make Roomba turn in place or drive straight. A negative velocity makes Roomba drive backward. Velocity is in range (-500 – 500 mm/s), radius (-2000 – 2000 mm). Special cases: straight = 32768 or 32767 = hex 8000 or 7FFF, turn in place clockwise = -1, turn in place counter-clockwise = 1

func (*Roomba) Full

func (this *Roomba) Full() error

Full command gives you complete control over Roomba by putting the OI into Full mode, and turning off the cliff, wheel-drop and internal charger safety features.

func (*Roomba) LEDs

func (this *Roomba) LEDs(check_robot, dock, spot, debris bool, power_color, power_intensity byte) error

LEDs command controls the LEDs common to all models of Roomba 500. The Clean/Power LED is specified by two data bytes: one for the color and the other for the intensity. Color: 0 = green, 255 = red. Intermediate values are intermediate colors (orange, yellow, etc). Intensitiy: 0 = off, 255 = full intensity. Intermediate values are intermediate intensities.

func (*Roomba) Open

func (this *Roomba) Open(baud uint) error

Configures and opens the given serial port.

func (*Roomba) Passive

func (this *Roomba) Passive() error

Passive switches Roomba to passive mode by sending the Start command.

func (*Roomba) PauseStream

func (this *Roomba) PauseStream()

PauseStream command lets you stop steam without clearing the list of requested packets.

func (*Roomba) Power

func (this *Roomba) Power() error

Power command powers down Roomba.

func (*Roomba) QueryList

func (this *Roomba) QueryList(packet_ids []byte) ([][]byte, error)

QueryList command lets you ask for a list of sensor packets. The result is returned once, as in the Sensors command. The robot returns the packets in / the order you specify.

func (*Roomba) Read

func (this *Roomba) Read(p []byte) (n int, err error)

Reads bytes from the serial port.

func (*Roomba) ReadStream

func (this *Roomba) ReadStream(packet_ids []byte, out chan<- [][]byte)

func (*Roomba) Safe

func (this *Roomba) Safe() error

This command puts the OI into Safe mode, enabling user control of Roomba. It turns off all LEDs.

func (*Roomba) SeekDock

func (this *Roomba) SeekDock() error

SeekDock command sends Roomba to the dock.

func (*Roomba) Sensors

func (this *Roomba) Sensors(packet_id byte) ([]byte, error)

Sensors command requests the OI to send a packet of sensor data bytes. There are 58 different sensor data packets. Each provides a value of a specific sensor or group of sensors.

func (*Roomba) Spot

func (this *Roomba) Spot() error

Spot command starts the Spot cleaning mode.

func (*Roomba) Start

func (this *Roomba) Start() error

Start command starts the OI. You must always send the Start command before sending any other commands to the OI. Note: Use the Start command (128) to change the mode to Passive.

func (*Roomba) Stop

func (this *Roomba) Stop() error

Stop commands is equivalent to Drive(0, 0).

func (*Roomba) Stream

func (this *Roomba) Stream(packet_ids []byte) (<-chan [][]byte, error)

Stream command starts a stream of data packets. The list of packets requested is sent every 15 ms, which is the rate Roomba uses to update data. This method of requesting sensor data is best if you are controlling Roomba over a wireless network (which has poor real-time characteristics) with software running on a desktop computer.

func (*Roomba) Write

func (this *Roomba) Write(opcode byte, p []byte) error

Writes the given opcode byte and a sequence of data bytes to the serial port.

func (*Roomba) WriteByte

func (this *Roomba) WriteByte(opcode byte) error

Writes a single byte to the serial port.

Directories

Path Synopsis
Package constants defines values for OpenInterface op codes, sensor codes and sensor packet lengths among others.
Package constants defines values for OpenInterface op codes, sensor codes and sensor packet lengths among others.
Package sim defines a limited OpenInterface simulator type that's mainly used for testing.
Package sim defines a limited OpenInterface simulator type that's mainly used for testing.

Jump to

Keyboard shortcuts

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