// NewWiichuckDriver creates a WiichuckDriver with specified i2c interface. // // It adds the following events: // "z"- Gets triggered every interval amount of time if the z button is pressed // "c" - Gets triggered every interval amount of time if the c button is pressed // "joystick" - Gets triggered every "interval" amount of time if a joystick event occurred, you can access values x, y // "error" - Gets triggered whenever the WiichuckDriver encounters an error func NewWiichuckDriver(a I2c, v ...time.Duration) *WiichuckDriver { w := &WiichuckDriver{ name: "Wiichuck", connection: a, interval: 10 * time.Millisecond, pauseTime: 1 * time.Millisecond, Eventer: gobot.NewEventer(), joystick: map[string]float64{ "sy_origin": -1, "sx_origin": -1, }, data: map[string]float64{ "sx": 0, "sy": 0, "z": 0, "c": 0, }, } if len(v) > 0 { w.interval = v[0] } w.AddEvent(Z) w.AddEvent(C) w.AddEvent(Joystick) w.AddEvent(Error) return w }
// NewAnalogSensorDriver returns a new AnalogSensorDriver with a polling interval of // 10 Milliseconds given an AnalogReader and pin. // // Optionally accepts: // time.Duration: Interval at which the AnalogSensor is polled for new information // // Adds the following API Commands: // "Read" - See AnalogSensor.Read func NewAnalogSensorDriver(a AnalogReader, pin string, v ...time.Duration) *AnalogSensorDriver { d := &AnalogSensorDriver{ name: "AnalogSensor", connection: a, pin: pin, Eventer: gobot.NewEventer(), Commander: gobot.NewCommander(), interval: 10 * time.Millisecond, halt: make(chan bool), } if len(v) > 0 { d.interval = v[0] } d.AddEvent(Data) d.AddEvent(Error) d.AddCommand("Read", func(params map[string]interface{}) interface{} { val, err := d.Read() return map[string]interface{}{"val": val, "err": err} }) return d }
// NewDriver creates a new pebble driver // Adds following events: // button - Sent when a pebble button is pressed // accel - Pebble watch acceleromenter data // tab - When a pebble watch tap event is detected // And the following API commands: // "publish_event" // "send_notification" // "pending_message" func NewDriver(adaptor *Adaptor) *Driver { p := &Driver{ name: "Pebble", connection: adaptor, Messages: []string{}, Eventer: gobot.NewEventer(), Commander: gobot.NewCommander(), } p.AddEvent("button") p.AddEvent("accel") p.AddEvent("tap") p.AddCommand("publish_event", func(params map[string]interface{}) interface{} { p.PublishEvent(params["name"].(string), params["data"].(string)) return nil }) p.AddCommand("send_notification", func(params map[string]interface{}) interface{} { p.SendNotification(params["message"].(string)) return nil }) p.AddCommand("pending_message", func(params map[string]interface{}) interface{} { return p.PendingMessage() }) return p }
// New returns a new Client func New() *Client { c := &Client{ ProtocolVersion: "", FirmwareName: "", connection: nil, pins: []Pin{}, analogPins: []int{}, connected: false, Eventer: gobot.NewEventer(), } for _, s := range []string{ "FirmwareQuery", "CapabilityQuery", "AnalogMappingQuery", "ProtocolVersion", "I2cReply", "StringData", "Error", } { c.AddEvent(s) } return c }
// NewDriver creates a Parrot Minidrone Driver func NewDriver(a *ble.ClientAdaptor) *Driver { n := &Driver{ name: "Minidrone", connection: a, Pcmd: Pcmd{ Flag: 0, Roll: 0, Pitch: 0, Yaw: 0, Gaz: 0, Psi: 0, }, Eventer: gobot.NewEventer(), } n.AddEvent(Battery) n.AddEvent(FlightStatus) n.AddEvent(Takeoff) n.AddEvent(Flying) n.AddEvent(Hovering) n.AddEvent(Landing) n.AddEvent(Landed) n.AddEvent(Emergency) n.AddEvent(Rolling) return n }
// NewMCP23017Driver creates a new driver with specified i2c interface. func NewMCP23017Driver(a I2c, conf MCP23017Config, deviceAddress int, v ...time.Duration) *MCP23017Driver { m := &MCP23017Driver{ name: "MCP23017", connection: a, conf: conf, mcp23017Address: deviceAddress, Commander: gobot.NewCommander(), Eventer: gobot.NewEventer(), } m.AddCommand("WriteGPIO", func(params map[string]interface{}) interface{} { pin := params["pin"].(uint8) val := params["val"].(uint8) port := params["port"].(string) err := m.WriteGPIO(pin, val, port) return map[string]interface{}{"err": err} }) m.AddCommand("ReadGPIO", func(params map[string]interface{}) interface{} { pin := params["pin"].(uint8) port := params["port"].(string) val, err := m.ReadGPIO(pin, port) return map[string]interface{}{"val": val, "err": err} }) return m }
// NewCameraDriver creates a new driver with specified source. // It also creates a start function to either set camera as a File or Camera capture. func NewCameraDriver(source interface{}, v ...time.Duration) *CameraDriver { c := &CameraDriver{ name: "Camera", Eventer: gobot.NewEventer(), Source: source, interval: 10 * time.Millisecond, start: func(c *CameraDriver) (err error) { switch v := c.Source.(type) { case string: c.camera = cv.NewFileCapture(v) case int: c.camera = cv.NewCameraCapture(v) default: return errors.New("Unknown camera source") } return }, } if len(v) > 0 { c.interval = v[0] } c.AddEvent(Frame) return c }
// NewDriver creates an Driver for the ARDrone. // // It add the following events: // 'flying' - Sent when the device has taken off. func NewDriver(connection *Adaptor) *Driver { d := &Driver{ name: "ARDrone", connection: connection, Eventer: gobot.NewEventer(), } d.AddEvent(Flying) return d }
// NewGenericAccessDriver creates a GenericAccessDriver func NewGenericAccessDriver(a *ClientAdaptor) *GenericAccessDriver { n := &GenericAccessDriver{ name: "GenericAccess", connection: a, Eventer: gobot.NewEventer(), } return n }
// NewDeviceInformationDriver creates a DeviceInformationDriver func NewDeviceInformationDriver(a *ClientAdaptor) *DeviceInformationDriver { n := &DeviceInformationDriver{ name: "DeviceInformation", connection: a, Eventer: gobot.NewEventer(), } return n }
// NewBatteryDriver creates a BatteryDriver func NewBatteryDriver(a *ClientAdaptor) *BatteryDriver { n := &BatteryDriver{ name: "Battery", connection: a, Eventer: gobot.NewEventer(), } return n }
// NewAdaptor creates new Photon adaptor with deviceId and accessToken // using api.particle.io server as default func NewAdaptor(deviceID string, accessToken string) *Adaptor { return &Adaptor{ name: "Particle", DeviceID: deviceID, AccessToken: accessToken, servoPins: make(map[string]bool), APIServer: "https://api.particle.io", Eventer: gobot.NewEventer(), } }
// NewDriver creates a Driver for a Sphero Ollie func NewDriver(a *ble.ClientAdaptor) *Driver { n := &Driver{ name: "Ollie", connection: a, Eventer: gobot.NewEventer(), packetChannel: make(chan *packet, 1024), } return n }
// NewDriver returns a new audio Driver. It accepts: // // *Adaptor: The audio adaptor to use for the driver // string: The filename of the audio to start playing // func NewDriver(a *Adaptor, filename string) *Driver { return &Driver{ name: "Audio", connection: a, interval: 500 * time.Millisecond, filename: filename, halt: make(chan bool, 0), Eventer: gobot.NewEventer(), Commander: gobot.NewCommander(), } }
// NewDriver creates a new leap motion driver // // Adds the following events: // "message" - Gets triggered when receiving a message from leap motion // "hand" - Gets triggered per-message when leap motion detects a hand // "gesture" - Gets triggered per-message when leap motion detects a hand func NewDriver(a *Adaptor) *Driver { l := &Driver{ name: "LeapMotion", connection: a, Eventer: gobot.NewEventer(), } l.AddEvent(MessageEvent) l.AddEvent(HandEvent) l.AddEvent(GestureEvent) return l }
func newMockFirmataBoard() *mockFirmataBoard { m := &mockFirmataBoard{ Eventer: gobot.NewEventer(), disconnectError: nil, pins: make([]client.Pin, 100), } m.pins[1].Value = 1 m.pins[15].Value = 133 m.AddEvent("I2cReply") return m }
// NewMPL115A2Driver creates a new driver with specified i2c interface func NewMPL115A2Driver(a I2c, v ...time.Duration) *MPL115A2Driver { m := &MPL115A2Driver{ name: "MPL115A2", connection: a, Eventer: gobot.NewEventer(), interval: 10 * time.Millisecond, } if len(v) > 0 { m.interval = v[0] } m.AddEvent(Error) return m }
func NewPingDriver(adaptor *loopbackAdaptor, pin string) *pingDriver { t := &pingDriver{ name: "Ping", connection: adaptor, pin: pin, Eventer: gobot.NewEventer(), Commander: gobot.NewCommander(), } t.AddEvent("ping") t.AddCommand("ping", func(params map[string]interface{}) interface{} { return t.Ping() }) return t }
// NewDriver creates a Neurosky Driver // and adds the following events: // // extended - user's current extended level // signal - shows signal strength // attention - user's current attention level // meditation - user's current meditation level // blink - user's current blink level // wave - shows wave data // eeg - showing eeg data func NewDriver(a *Adaptor) *Driver { n := &Driver{ name: "Neurosky", connection: a, Eventer: gobot.NewEventer(), } n.AddEvent(Extended) n.AddEvent(Signal) n.AddEvent(Attention) n.AddEvent(Meditation) n.AddEvent(Blink) n.AddEvent(Wave) n.AddEvent(EEG) n.AddEvent(Error) return n }
// NewGroveTemperatureSensorDriver returns a new GroveTemperatureSensorDriver with a polling interval of // 10 Milliseconds given an AnalogReader and pin. // // Optionally accepts: // time.Duration: Interval at which the TemperatureSensor is polled for new information // // Adds the following API Commands: // "Read" - See AnalogSensor.Read func NewGroveTemperatureSensorDriver(a AnalogReader, pin string, v ...time.Duration) *GroveTemperatureSensorDriver { d := &GroveTemperatureSensorDriver{ connection: a, pin: pin, Eventer: gobot.NewEventer(), interval: 10 * time.Millisecond, halt: make(chan bool), } if len(v) > 0 { d.interval = v[0] } d.AddEvent(Data) d.AddEvent(Error) return d }
// NewDriver creates a new mavlink driver. // // It add the following events: // "packet" - triggered when a new packet is read // "message" - triggered when a new valid message is processed func NewDriver(a *Adaptor, v ...time.Duration) *Driver { m := &Driver{ name: "Mavlink", connection: a, Eventer: gobot.NewEventer(), interval: 10 * time.Millisecond, } if len(v) > 0 { m.interval = v[0] } m.AddEvent(PacketEvent) m.AddEvent(MessageEvent) m.AddEvent(ErrorIOEvent) m.AddEvent(ErrorMAVLinkEvent) return m }
// NewDriver returns a new Driver with a polling interval of // 10 Milliseconds given a Joystick Adaptor and json button configuration // file location. // // Optionally accepts: // time.Duration: Interval at which the Driver is polled for new information func NewDriver(a *Adaptor, config string, v ...time.Duration) *Driver { d := &Driver{ name: "Joystick", connection: a, Eventer: gobot.NewEventer(), configPath: config, poll: func() sdl.Event { return sdl.PollEvent() }, interval: 10 * time.Millisecond, halt: make(chan bool, 0), } if len(v) > 0 { d.interval = v[0] } d.AddEvent("error") return d }
// NewPIRMotionDriver returns a new PIRMotionDriver with a polling interval of // 10 Milliseconds given a DigitalReader and pin. // // Optionally accepts: // time.Duration: Interval at which the PIRMotionDriver is polled for new information func NewPIRMotionDriver(a DigitalReader, pin string, v ...time.Duration) *PIRMotionDriver { b := &PIRMotionDriver{ name: "PIRMotion", connection: a, pin: pin, Active: false, Eventer: gobot.NewEventer(), interval: 10 * time.Millisecond, halt: make(chan bool), } if len(v) > 0 { b.interval = v[0] } b.AddEvent(MotionDetected) b.AddEvent(MotionStopped) b.AddEvent(Error) return b }
// NewButtonDriver returns a new ButtonDriver with a polling interval of // 10 Milliseconds given a DigitalReader and pin. // // Optionally accepts: // time.Duration: Interval at which the ButtonDriver is polled for new information func NewButtonDriver(a DigitalReader, pin string, v ...time.Duration) *ButtonDriver { b := &ButtonDriver{ name: "Button", connection: a, pin: pin, Active: false, Eventer: gobot.NewEventer(), interval: 10 * time.Millisecond, halt: make(chan bool), } if len(v) > 0 { b.interval = v[0] } b.AddEvent(ButtonPush) b.AddEvent(ButtonRelease) b.AddEvent(Error) return b }
// NewDriver returns a new keyboard Driver. // func NewDriver() *Driver { k := &Driver{ name: "Keyboard", connect: func(k *Driver) (err error) { if err := configure(); err != nil { return err } k.stdin = os.Stdin return }, listen: func(k *Driver) { ctrlc := bytes{3} for { var keybuf bytes k.stdin.Read(keybuf[0:3]) if keybuf == ctrlc { proc, err := os.FindProcess(os.Getpid()) if err != nil { log.Fatal(err) } proc.Signal(os.Interrupt) break } k.Publish(Key, Parse(keybuf)) } }, Eventer: gobot.NewEventer(), } k.AddEvent(Key) return k }
// NewAdaptor returns a new Firmata Adaptor which optionally accepts: // // string: port the Adaptor uses to connect to a serial port with a baude rate of 57600 // io.ReadWriteCloser: connection the Adaptor uses to communication with the hardware // // If an io.ReadWriteCloser is not supplied, the Adaptor will open a connection // to a serial port with a baude rate of 57600. If an io.ReadWriteCloser // is supplied, then the Adaptor will use the provided io.ReadWriteCloser and use the // string port as a label to be displayed in the log and api. func NewAdaptor(args ...interface{}) *Adaptor { f := &Adaptor{ name: "Firmata", port: "", conn: nil, board: client.New(), openCommPort: func(port string) (io.ReadWriteCloser, error) { return serial.OpenPort(&serial.Config{Name: port, Baud: 57600}) }, Eventer: gobot.NewEventer(), } for _, arg := range args { switch arg.(type) { case string: f.port = arg.(string) case io.ReadWriteCloser: f.conn = arg.(io.ReadWriteCloser) } } return f }
func newTestDriver(adaptor *testAdaptor, name string, pin string) *testDriver { t := &testDriver{ name: name, connection: adaptor, pin: pin, Eventer: gobot.NewEventer(), Commander: gobot.NewCommander(), } t.AddEvent("TestEvent") t.AddCommand("TestDriverCommand", func(params map[string]interface{}) interface{} { name := params["name"].(string) return fmt.Sprintf("hello %v", name) }) t.AddCommand("DriverCommand", func(params map[string]interface{}) interface{} { name := params["name"].(string) return fmt.Sprintf("hello %v", name) }) return t }
// NewSpheroDriver returns a new SpheroDriver given a Sphero Adaptor. // // Adds the following API Commands: // "ConfigureLocator" - See SpheroDriver.ConfigureLocator // "Roll" - See SpheroDriver.Roll // "Stop" - See SpheroDriver.Stop // "GetRGB" - See SpheroDriver.GetRGB // "ReadLocator" - See SpheroDriver.ReadLocator // "SetBackLED" - See SpheroDriver.SetBackLED // "SetHeading" - See SpheroDriver.SetHeading // "SetStabilization" - See SpheroDriver.SetStabilization // "SetDataStreaming" - See SpheroDriver.SetDataStreaming // "SetRotationRate" - See SpheroDriver.SetRotationRate func NewSpheroDriver(a *Adaptor) *SpheroDriver { s := &SpheroDriver{ name: "Sphero", connection: a, Eventer: gobot.NewEventer(), Commander: gobot.NewCommander(), packetChannel: make(chan *packet, 1024), responseChannel: make(chan []uint8, 1024), } s.AddEvent(Error) s.AddEvent(Collision) s.AddEvent(SensorData) s.AddCommand("SetRGB", func(params map[string]interface{}) interface{} { r := uint8(params["r"].(float64)) g := uint8(params["g"].(float64)) b := uint8(params["b"].(float64)) s.SetRGB(r, g, b) return nil }) s.AddCommand("Roll", func(params map[string]interface{}) interface{} { speed := uint8(params["speed"].(float64)) heading := uint16(params["heading"].(float64)) s.Roll(speed, heading) return nil }) s.AddCommand("Stop", func(params map[string]interface{}) interface{} { s.Stop() return nil }) s.AddCommand("GetRGB", func(params map[string]interface{}) interface{} { return s.GetRGB() }) s.AddCommand("ReadLocator", func(params map[string]interface{}) interface{} { return s.ReadLocator() }) s.AddCommand("SetBackLED", func(params map[string]interface{}) interface{} { level := uint8(params["level"].(float64)) s.SetBackLED(level) return nil }) s.AddCommand("SetRotationRate", func(params map[string]interface{}) interface{} { level := uint8(params["level"].(float64)) s.SetRotationRate(level) return nil }) s.AddCommand("SetHeading", func(params map[string]interface{}) interface{} { heading := uint16(params["heading"].(float64)) s.SetHeading(heading) return nil }) s.AddCommand("SetStabilization", func(params map[string]interface{}) interface{} { on := params["enable"].(bool) s.SetStabilization(on) return nil }) s.AddCommand("SetDataStreaming", func(params map[string]interface{}) interface{} { N := uint16(params["N"].(float64)) M := uint16(params["M"].(float64)) Mask := uint32(params["Mask"].(float64)) Pcnt := uint8(params["Pcnt"].(float64)) Mask2 := uint32(params["Mask2"].(float64)) s.SetDataStreaming(DataStreamingConfig{N: N, M: M, Mask2: Mask2, Pcnt: Pcnt, Mask: Mask}) return nil }) s.AddCommand("ConfigureLocator", func(params map[string]interface{}) interface{} { Flags := uint8(params["Flags"].(float64)) X := int16(params["X"].(float64)) Y := int16(params["Y"].(float64)) YawTare := int16(params["YawTare"].(float64)) s.ConfigureLocator(LocatorConfig{Flags: Flags, X: X, Y: Y, YawTare: YawTare}) return nil }) return s }