From c129da61d3e8db08be922ba66c97cf44d175c5c7 Mon Sep 17 00:00:00 2001 From: Adrian Zankich Date: Tue, 10 Jun 2014 15:16:11 -0700 Subject: [PATCH] Make golint happy --- README.md | 8 +- api/api.go | 60 ++--- api/api_test.go | 10 +- connection.go | 14 +- device.go | 22 +- examples/ardrone_face_tracking.go | 4 +- examples/ardrone_ps3.go | 30 ++- examples/beaglebone_led_brightness.go | 6 +- examples/digispark_api.go | 2 +- examples/digispark_led_brightness.go | 6 +- examples/firmata_led_brightness.go | 6 +- examples/firmata_motor.go | 6 +- examples/firmata_servo.go | 4 +- examples/firmata_travis.go | 22 +- examples/hello_api.go | 2 +- examples/hello_api_auth.go | 2 +- examples/neurosky.go | 2 +- examples/pebble.go | 2 +- examples/pebble_accelerometer.go | 2 +- examples/spark_core_api.go | 2 +- examples/spark_core_led_brithgness.go | 6 +- examples/sphero_api.go | 2 +- examples/sphero_conways.go | 7 +- gobot/generate.go | 42 ++-- platforms/ardrone/ardrone_adaptor.go | 4 +- platforms/ardrone/ardrone_driver.go | 50 ++-- platforms/ardrone/test_helper.go | 22 +- platforms/beaglebone/analog_pin.go | 10 +- platforms/beaglebone/beaglebone_adaptor.go | 8 +- platforms/beaglebone/digital_pin.go | 22 +- platforms/beaglebone/i2c_device.go | 18 +- platforms/beaglebone/pwm_pin.go | 14 +- platforms/firmata/firmata.go | 266 ++++++++++----------- platforms/firmata/firmata_adaptor.go | 12 +- platforms/firmata/firmata_adaptor_test.go | 18 +- platforms/gpio/button_driver.go | 16 +- platforms/gpio/makey_button_driver.go | 16 +- platforms/gpio/motor_driver.go | 3 +- platforms/i2c/hmc6352_driver.go | 4 +- platforms/i2c/wiichuck_driver.go | 15 +- platforms/joystick/joystick_driver.go | 8 +- platforms/leap/leap_motion_adaptor.go | 2 +- platforms/leap/leap_motion_driver.go | 4 +- platforms/neurosky/neurosky_driver.go | 72 +++--- platforms/pebble/README.md | 2 +- platforms/spark/spark_core_adaptor.go | 21 +- platforms/sphero/sphero_driver.go | 69 +++--- platforms/sphero/test_helper.go | 6 +- robot.go | 22 +- test_helper.go | 44 ++-- 50 files changed, 507 insertions(+), 510 deletions(-) diff --git a/README.md b/README.md index ba204c7eb..ca77201bb 100644 --- a/README.md +++ b/README.md @@ -118,17 +118,17 @@ Install Gobot with: `go get -u github.com/hybridgroup/gobot` 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, require the `github.com/hybridgroup/gobot/api` package and instantiate the `Api` like this: +To activate the API, require the `github.com/hybridgroup/gobot/api` package and instantiate the `API` like this: ```go master := gobot.NewGobot() - api.NewApi(master).Start() + api.NewAPI(master).Start() ``` You can also specify the api host and port, and turn on authentication: ```go master := gobot.NewGobot() - server := api.NewApi(master) + server := api.NewAPI(master) server.Port = "4000" server.Username = "Gort" server.Password = "klaatu" @@ -150,7 +150,7 @@ Thank you! * We will look at the patch, test it out, and give you feedback. * Avoid doing minor whitespace changes, renamings, etc. along with merged content. These will be done by the maintainers from time to time but they can complicate merges and should be done seperately. * Take care to maintain the existing coding style. -* `go fmt` your code. +* `golint` and `go fmt` your code. * Add unit tests for any new or changed functionality. * All pull requests should be "fast forward" * If there are commits after yours use “git rebase -i ” diff --git a/api/api.go b/api/api.go index dfc20b901..42b56c121 100644 --- a/api/api.go +++ b/api/api.go @@ -27,7 +27,7 @@ type api struct { start func(*api) } -func NewApi(g *gobot.Gobot) *api { +func NewAPI(g *gobot.Gobot) *api { return &api{ gobot: g, start: func(a *api) { @@ -82,54 +82,54 @@ func (a *api) Start() { }) a.server.Get("/robots/:robotname/commands", func(params martini.Params, res http.ResponseWriter, req *http.Request) { - a.robot_commands(params["robotname"], res, req) + a.robotCommands(params["robotname"], res, req) }) - robot_command_route := "/robots/:robotname/commands/:command" + robotCommandRoute := "/robots/:robotname/commands/:command" - a.server.Get(robot_command_route, func(params martini.Params, res http.ResponseWriter, req *http.Request) { + a.server.Get(robotCommandRoute, func(params martini.Params, res http.ResponseWriter, req *http.Request) { a.executeRobotCommand(params["robotname"], params["command"], res, req) }) - a.server.Post(robot_command_route, func(params martini.Params, res http.ResponseWriter, req *http.Request) { + a.server.Post(robotCommandRoute, func(params martini.Params, res http.ResponseWriter, req *http.Request) { a.executeRobotCommand(params["robotname"], params["command"], res, req) }) a.server.Get("/robots/:robotname/devices", func(params martini.Params, res http.ResponseWriter, req *http.Request) { - a.robot_devices(params["robotname"], res, req) + a.robotDevices(params["robotname"], res, req) }) a.server.Get("/robots/:robotname/devices/:devicename", func(params martini.Params, res http.ResponseWriter, req *http.Request) { - a.robot_device(params["robotname"], params["devicename"], res, req) + a.robotDevice(params["robotname"], params["devicename"], res, req) }) a.server.Get("/robots/:robotname/devices/:devicename/commands", func(params martini.Params, res http.ResponseWriter, req *http.Request) { - a.robot_device_commands(params["robotname"], params["devicename"], res, req) + a.robotDeviceCommands(params["robotname"], params["devicename"], res, req) }) - command_route := "/robots/:robotname/devices/:devicename/commands/:command" + commandRoute := "/robots/:robotname/devices/:devicename/commands/:command" - a.server.Get(command_route, func(params martini.Params, res http.ResponseWriter, req *http.Request) { + a.server.Get(commandRoute, func(params martini.Params, res http.ResponseWriter, req *http.Request) { a.executeCommand(params["robotname"], params["devicename"], params["command"], res, req) }) - a.server.Post(command_route, func(params martini.Params, res http.ResponseWriter, req *http.Request) { + a.server.Post(commandRoute, func(params martini.Params, res http.ResponseWriter, req *http.Request) { a.executeCommand(params["robotname"], params["devicename"], params["command"], res, req) }) a.server.Get("/robots/:robotname/connections", func(params martini.Params, res http.ResponseWriter, req *http.Request) { - a.robot_connections(params["robotname"], res, req) + a.robotConnections(params["robotname"], res, req) }) a.server.Get("/robots/:robotname/connections/:connectionname", func(params martini.Params, res http.ResponseWriter, req *http.Request) { - a.robot_connection(params["robotname"], params["connectionname"], res, req) + a.robotConnection(params["robotname"], params["connectionname"], res, req) }) a.start(a) } func (a *api) robots(res http.ResponseWriter, req *http.Request) { - jsonRobots := make([]*gobot.JsonRobot, 0) + jsonRobots := []*gobot.JSONRobot{} for _, robot := range a.gobot.Robots { - jsonRobots = append(jsonRobots, robot.ToJson()) + jsonRobots = append(jsonRobots, robot.ToJSON()) } data, _ := json.Marshal(jsonRobots) res.Header().Set("Content-Type", "application/json; charset=utf-8") @@ -137,53 +137,53 @@ func (a *api) robots(res http.ResponseWriter, req *http.Request) { } func (a *api) robot(name string, res http.ResponseWriter, req *http.Request) { - data, _ := json.Marshal(a.gobot.Robot(name).ToJson()) + data, _ := json.Marshal(a.gobot.Robot(name).ToJSON()) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } -func (a *api) robot_commands(name string, res http.ResponseWriter, req *http.Request) { +func (a *api) robotCommands(name string, res http.ResponseWriter, req *http.Request) { data, _ := json.Marshal(a.gobot.Robot(name).RobotCommands) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } -func (a *api) robot_devices(name string, res http.ResponseWriter, req *http.Request) { +func (a *api) robotDevices(name string, res http.ResponseWriter, req *http.Request) { devices := a.gobot.Robot(name).Devices() - jsonDevices := make([]*gobot.JsonDevice, 0) + jsonDevices := []*gobot.JSONDevice{} for _, device := range devices { - jsonDevices = append(jsonDevices, device.ToJson()) + jsonDevices = append(jsonDevices, device.ToJSON()) } data, _ := json.Marshal(jsonDevices) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } -func (a *api) robot_device(robot string, device string, res http.ResponseWriter, req *http.Request) { - data, _ := json.Marshal(a.gobot.Robot(robot).Device(device).ToJson()) +func (a *api) robotDevice(robot string, device string, res http.ResponseWriter, req *http.Request) { + data, _ := json.Marshal(a.gobot.Robot(robot).Device(device).ToJSON()) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } -func (a *api) robot_device_commands(robot string, device string, res http.ResponseWriter, req *http.Request) { +func (a *api) robotDeviceCommands(robot string, device string, res http.ResponseWriter, req *http.Request) { data, _ := json.Marshal(a.gobot.Robot(robot).Device(device).Commands()) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } -func (a *api) robot_connections(name string, res http.ResponseWriter, req *http.Request) { +func (a *api) robotConnections(name string, res http.ResponseWriter, req *http.Request) { connections := a.gobot.Robot(name).Connections() - jsonConnections := make([]*gobot.JsonConnection, 0) + jsonConnections := []*gobot.JSONConnection{} for _, connection := range connections { - jsonConnections = append(jsonConnections, connection.ToJson()) + jsonConnections = append(jsonConnections, connection.ToJSON()) } data, _ := json.Marshal(jsonConnections) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } -func (a *api) robot_connection(robot string, connection string, res http.ResponseWriter, req *http.Request) { - data, _ := json.Marshal(a.gobot.Robot(robot).Connection(connection).ToJson()) +func (a *api) robotConnection(robot string, connection string, res http.ResponseWriter, req *http.Request) { + data, _ := json.Marshal(a.gobot.Robot(robot).Connection(connection).ToJSON()) res.Header().Set("Content-Type", "application/json; charset=utf-8") res.Write(data) } @@ -196,7 +196,7 @@ func (a *api) executeCommand(robotname string, devicename string, commandname st commands := robot.Commands().([]string) for command := range commands { if commands[command] == commandname { - ret := make([]interface{}, 0) + ret := []interface{}{} for _, v := range gobot.Call(robot.Driver, commandname, body) { ret = append(ret, v.Interface()) } @@ -221,7 +221,7 @@ func (a *api) executeRobotCommand(robotname string, commandname string, res http in[0] = reflect.ValueOf(body) command := robot.Commands[commandname] if command != nil { - ret := make([]interface{}, 0) + ret := []interface{}{} for _, v := range reflect.ValueOf(robot.Commands[commandname]).Call(in) { ret = append(ret, v.Interface()) } diff --git a/api/api_test.go b/api/api_test.go index 17d80284f..b2bc21572 100644 --- a/api/api_test.go +++ b/api/api_test.go @@ -19,7 +19,7 @@ var _ = Describe("API", func() { BeforeEach(func() { m = gobot.NewGobot() - a = NewApi(m) + a = NewAPI(m) a.start = func(m *api) {} m.Robots = []*gobot.Robot{ @@ -51,7 +51,7 @@ var _ = Describe("API", func() { It("should return all robot devices", func() { request, _ := http.NewRequest("GET", "/robots/Robot%201/devices", nil) response := httptest.NewRecorder() - a.robot_devices("Robot 1", response, request) + a.robotDevices("Robot 1", response, request) body, _ := ioutil.ReadAll(response.Body) var i []map[string]interface{} json.Unmarshal(body, &i) @@ -60,7 +60,7 @@ var _ = Describe("API", func() { PIt("should return robot commands", func() { request, _ := http.NewRequest("GET", "/robots/Robot%201/commands", nil) response := httptest.NewRecorder() - a.robot_commands("Robot 1", response, request) + a.robotCommands("Robot 1", response, request) body, _ := ioutil.ReadAll(response.Body) var i []string json.Unmarshal(body, &i) @@ -89,7 +89,7 @@ var _ = Describe("API", func() { It("should return robot device", func() { request, _ := http.NewRequest("GET", "/robots/Robot%201/devices/Device%201", nil) response := httptest.NewRecorder() - a.robot_device("Robot 1", "Device 1", response, request) + a.robotDevice("Robot 1", "Device 1", response, request) body, _ := ioutil.ReadAll(response.Body) var i map[string]interface{} json.Unmarshal(body, &i) @@ -98,7 +98,7 @@ var _ = Describe("API", func() { It("should return device commands", func() { request, _ := http.NewRequest("GET", "/robots/Robot%201/devices/Device%201/commands", nil) response := httptest.NewRecorder() - a.robot_device_commands("Robot 1", "Device 1", response, request) + a.robotDeviceCommands("Robot 1", "Device 1", response, request) body, _ := ioutil.ReadAll(response.Body) var i []string json.Unmarshal(body, &i) diff --git a/connection.go b/connection.go index 96c833e68..bf3c48b28 100644 --- a/connection.go +++ b/connection.go @@ -11,7 +11,7 @@ type Connection interface { Finalize() bool } -type JsonConnection struct { +type JSONConnection struct { Name string `json:"name"` Port string `json:"port"` Adaptor string `json:"adaptor"` @@ -75,10 +75,10 @@ func (c *connection) Finalize() bool { return c.Adaptor.Finalize() } -func (c *connection) ToJson() *JsonConnection { - jsonConnection := new(JsonConnection) - jsonConnection.Name = c.Name - jsonConnection.Port = c.Port - jsonConnection.Adaptor = c.Type - return jsonConnection +func (c *connection) ToJSON() *JSONConnection { + return &JSONConnection{ + Name: c.Name, + Port: c.Port, + Adaptor: c.Type, + } } diff --git a/device.go b/device.go index af78fe0a1..87c961747 100644 --- a/device.go +++ b/device.go @@ -16,10 +16,10 @@ type Device interface { getName() string } -type JsonDevice struct { +type JSONDevice struct { Name string `json:"name"` Driver string `json:"driver"` - Connection *JsonConnection `json:"connection"` + Connection *JSONConnection `json:"connection"` Commands []string `json:"commands"` } @@ -97,13 +97,13 @@ func (d *device) Commands() interface{} { return FieldByNamePtr(d.Driver, "Commands").Interface() } -func (d *device) ToJson() *JsonDevice { - jsonDevice := new(JsonDevice) - jsonDevice.Name = d.Name - jsonDevice.Driver = d.Type - jsonDevice.Connection = d.Robot.Connection(FieldByNamePtr(FieldByNamePtr(d.Driver, "Adaptor"). - Interface().(AdaptorInterface), "Name"). - Interface().(string)).ToJson() - jsonDevice.Commands = FieldByNamePtr(d.Driver, "Commands").Interface().([]string) - return jsonDevice +func (d *device) ToJSON() *JSONDevice { + return &JSONDevice{ + Name: d.Name, + Driver: d.Type, + Connection: d.Robot.Connection(FieldByNamePtr(FieldByNamePtr(d.Driver, "Adaptor"). + Interface().(AdaptorInterface), "Name"). + Interface().(string)).ToJSON(), + Commands: FieldByNamePtr(d.Driver, "Commands").Interface().([]string), + } } diff --git a/examples/ardrone_face_tracking.go b/examples/ardrone_face_tracking.go index 384b75665..d136804ea 100644 --- a/examples/ardrone_face_tracking.go +++ b/examples/ardrone_face_tracking.go @@ -53,8 +53,8 @@ func main() { } if face != nil { opencv.DrawRectangles(i, []*cv.Rect{face}, 0, 255, 0, 5) - center_x := float64(image.Width()) * 0.5 - turn := -(float64(face.X()) - center_x) / center_x + centerX := float64(image.Width()) * 0.5 + turn := -(float64(face.X()) - centerX) / centerX fmt.Println("turning:", turn) if turn < 0 { drone.Clockwise(math.Abs(turn * 0.4)) diff --git a/examples/ardrone_ps3.go b/examples/ardrone_ps3.go index 1d2d5378e..094f84e69 100644 --- a/examples/ardrone_ps3.go +++ b/examples/ardrone_ps3.go @@ -24,8 +24,8 @@ func main() { work := func() { offset := 32767.0 - right_stick := pair{x: 0, y: 0} - left_stick := pair{x: 0, y: 0} + rightStick := pair{x: 0, y: 0} + leftStick := pair{x: 0, y: 0} gobot.On(joystick.Events["square_press"], func(data interface{}) { drone.TakeOff() @@ -38,31 +38,31 @@ func main() { }) gobot.On(joystick.Events["left_x"], func(data interface{}) { val := float64(data.(int16)) - if left_stick.x != val { - left_stick.x = val + if leftStick.x != val { + leftStick.x = val } }) gobot.On(joystick.Events["left_y"], func(data interface{}) { val := float64(data.(int16)) - if left_stick.y != val { - left_stick.y = val + if leftStick.y != val { + leftStick.y = val } }) gobot.On(joystick.Events["right_x"], func(data interface{}) { val := float64(data.(int16)) - if right_stick.x != val { - right_stick.x = val + if rightStick.x != val { + rightStick.x = val } }) gobot.On(joystick.Events["right_y"], func(data interface{}) { val := float64(data.(int16)) - if right_stick.y != val { - right_stick.y = val + if rightStick.y != val { + rightStick.y = val } }) gobot.Every(10*time.Millisecond, func() { - pair := left_stick + pair := leftStick if pair.y < -10 { drone.Forward(validatePitch(pair.y, offset)) } else if pair.y > 10 { @@ -81,7 +81,7 @@ func main() { }) gobot.Every(10*time.Millisecond, func() { - pair := right_stick + pair := rightStick if pair.y < -10 { drone.Up(validatePitch(pair.y, offset)) } else if pair.y > 10 { @@ -111,10 +111,8 @@ func validatePitch(data float64, offset float64) float64 { if value >= 0.1 { if value <= 1.0 { return float64(int(value*100)) / 100 - } else { - return 1.0 } - } else { - return 0.0 + return 1.0 } + return 0.0 } diff --git a/examples/beaglebone_led_brightness.go b/examples/beaglebone_led_brightness.go index a4ead71fe..3d2141d3e 100644 --- a/examples/beaglebone_led_brightness.go +++ b/examples/beaglebone_led_brightness.go @@ -14,13 +14,13 @@ func main() { work := func() { brightness := uint8(0) - fade_amount := uint8(5) + fadeAmount := uint8(5) gobot.Every(100*time.Millisecond, func() { led.Brightness(brightness) - brightness = brightness + fade_amount + brightness = brightness + fadeAmount if brightness == 0 || brightness == 255 { - fade_amount = -fade_amount + fadeAmount = -fadeAmount } }) } diff --git a/examples/digispark_api.go b/examples/digispark_api.go index adbd4fe9b..fa4374783 100644 --- a/examples/digispark_api.go +++ b/examples/digispark_api.go @@ -9,7 +9,7 @@ import ( func main() { gbot := gobot.NewGobot() - api.NewApi(gbot).Start() + api.NewAPI(gbot).Start() digisparkAdaptor := digispark.NewDigisparkAdaptor("Digispark") led := gpio.NewLedDriver(digisparkAdaptor, "led", "0") diff --git a/examples/digispark_led_brightness.go b/examples/digispark_led_brightness.go index 0dd87a2ec..4f46d1365 100644 --- a/examples/digispark_led_brightness.go +++ b/examples/digispark_led_brightness.go @@ -15,13 +15,13 @@ func main() { work := func() { brightness := uint8(0) - fade_amount := uint8(15) + fadeAmount := uint8(15) gobot.Every(100*time.Millisecond, func() { led.Brightness(brightness) - brightness = brightness + fade_amount + brightness = brightness + fadeAmount if brightness == 0 || brightness == 255 { - fade_amount = -fade_amount + fadeAmount = -fadeAmount } }) } diff --git a/examples/firmata_led_brightness.go b/examples/firmata_led_brightness.go index 9cf89132e..74b25693e 100644 --- a/examples/firmata_led_brightness.go +++ b/examples/firmata_led_brightness.go @@ -14,13 +14,13 @@ func main() { work := func() { brightness := uint8(0) - fade_amount := uint8(15) + fadeAmount := uint8(15) gobot.Every(100*time.Millisecond, func() { led.Brightness(brightness) - brightness = brightness + fade_amount + brightness = brightness + fadeAmount if brightness == 0 || brightness == 255 { - fade_amount = -fade_amount + fadeAmount = -fadeAmount } }) } diff --git a/examples/firmata_motor.go b/examples/firmata_motor.go index 1abf72d23..3e69fd622 100644 --- a/examples/firmata_motor.go +++ b/examples/firmata_motor.go @@ -14,13 +14,13 @@ func main() { work := func() { speed := byte(0) - fade_amount := byte(15) + fadeAmount := byte(15) gobot.Every(100*time.Millisecond, func() { motor.Speed(speed) - speed = speed + fade_amount + speed = speed + fadeAmount if speed == 0 || speed == 255 { - fade_amount = -fade_amount + fadeAmount = -fadeAmount } }) } diff --git a/examples/firmata_servo.go b/examples/firmata_servo.go index b6e0686e9..cb16d6713 100644 --- a/examples/firmata_servo.go +++ b/examples/firmata_servo.go @@ -21,8 +21,8 @@ func main() { }) } - gbot.Robot = append(gbot.Robot, + gbot.Robots = append(gbot.Robots, gobot.NewRobot("servoBot", []gobot.Connection{firmataAdaptor}, []gobot.Device{servo}, work)) - gbott.Start() + gbot.Start() } diff --git a/examples/firmata_travis.go b/examples/firmata_travis.go index a633a8cea..b37bfdb67 100644 --- a/examples/firmata_travis.go +++ b/examples/firmata_travis.go @@ -27,9 +27,9 @@ type TravisResponse struct { } func resetLeds(robot *gobot.Robot) { - gobot.Call(robot.GetDevice("red").Driver, "Off") - gobot.Call(robot.GetDevice("green").Driver, "Off") - gobot.Call(robot.GetDevice("blue").Driver, "Off") + gobot.Call(robot.Device("red").Driver, "Off") + gobot.Call(robot.Device("green").Driver, "Off") + gobot.Call(robot.Device("blue").Driver, "Off") } func checkTravis(robot *gobot.Robot) { @@ -38,7 +38,7 @@ func checkTravis(robot *gobot.Robot) { name := "gobot" //name := "broken-arrow" fmt.Printf("Checking repo %s/%s\n", user, name) - gobot.Call(robot.GetDevice("blue").Driver, "On") + gobot.Call(robot.Device("blue").Driver, "On") resp, err := http.Get(fmt.Sprintf("https://api.travis-ci.org/repos/%s/%s.json", user, name)) defer resp.Body.Close() if err != nil { @@ -52,23 +52,23 @@ func checkTravis(robot *gobot.Robot) { json.Unmarshal(body, &travis) resetLeds(robot) if travis.LastBuildStatus == 0 { - gobot.Call(robot.GetDevice("green").Driver, "On") + gobot.Call(robot.Device("green").Driver, "On") } else { - gobot.Call(robot.GetDevice("red").Driver, "On") + gobot.Call(robot.Device("red").Driver, "On") } } func main() { master := gobot.NewGobot() firmataAdaptor := firmata.NewFirmataAdaptor("firmata", "/dev/ttyACM0") - red := gpio.NewLedDriver(firmata, "red", "7") - green := gpio.NewLedDriver(firmata, "green", "6") - blue := gpio.NewLedDriver(firmata, "blue", "5") + red := gpio.NewLedDriver(firmataAdaptor, "red", "7") + green := gpio.NewLedDriver(firmataAdaptor, "green", "6") + blue := gpio.NewLedDriver(firmataAdaptor, "blue", "5") work := func() { - checkTravis(master.FindRobot("travis")) + checkTravis(master.Robot("travis")) gobot.Every(10*time.Second, func() { - checkTravis(master.FindRobot("travis")) + checkTravis(master.Robot("travis")) }) } diff --git a/examples/hello_api.go b/examples/hello_api.go index 41ebb9816..325d92c1f 100644 --- a/examples/hello_api.go +++ b/examples/hello_api.go @@ -13,7 +13,7 @@ func Hello(params map[string]interface{}) string { func main() { master := gobot.NewGobot() - api.NewApi(master).Start() + api.NewAPI(master).Start() hello := gobot.NewRobot("hello", nil, nil, nil) hello.Commands = map[string]interface{}{"Hello": Hello} diff --git a/examples/hello_api_auth.go b/examples/hello_api_auth.go index ffb0f988c..7f4760154 100644 --- a/examples/hello_api_auth.go +++ b/examples/hello_api_auth.go @@ -14,7 +14,7 @@ func Hello(params map[string]interface{}) string { func main() { master := gobot.NewGobot() - server := api.NewApi(master) + server := api.NewAPI(master) server.Username = "gort" server.Password = "klatuu" server.Start() diff --git a/examples/neurosky.go b/examples/neurosky.go index 2dc399c1f..541b326d4 100644 --- a/examples/neurosky.go +++ b/examples/neurosky.go @@ -32,7 +32,7 @@ func main() { fmt.Println("Wave", data) }) gobot.On(neuro.Events["EEG"], func(data interface{}) { - eeg := data.(gobotNeurosky.EEG) + eeg := data.(neurosky.EEG) fmt.Println("Delta", eeg.Delta) fmt.Println("Theta", eeg.Theta) fmt.Println("LoAlpha", eeg.LoAlpha) diff --git a/examples/pebble.go b/examples/pebble.go index 6ea7c1cd9..e1b60dc85 100644 --- a/examples/pebble.go +++ b/examples/pebble.go @@ -9,7 +9,7 @@ import ( func main() { master := gobot.NewGobot() - api.NewApi(master).Start() + api.NewAPI(master).Start() pebbleAdaptor := pebble.NewPebbleAdaptor("pebble") pebbleDriver := pebble.NewPebbleDriver(pebbleAdaptor, "pebble") diff --git a/examples/pebble_accelerometer.go b/examples/pebble_accelerometer.go index 7c3b375d3..90cf6c1e6 100644 --- a/examples/pebble_accelerometer.go +++ b/examples/pebble_accelerometer.go @@ -9,7 +9,7 @@ import ( func main() { master := gobot.NewGobot() - api.NewApi(master).Start() + api.NewAPI(master).Start() pebbleAdaptor := pebble.NewPebbleAdaptor("pebble") pebbleDriver := pebble.NewPebbleDriver(pebbleAdaptor, "pebble") diff --git a/examples/spark_core_api.go b/examples/spark_core_api.go index 707051f5a..8794cd51f 100644 --- a/examples/spark_core_api.go +++ b/examples/spark_core_api.go @@ -10,7 +10,7 @@ import ( func main() { master := gobot.NewGobot() - api.NewApi(master).Start() + api.NewAPI(master).Start() sparkCore := spark.NewSparkCoreAdaptor("spark", "device_id", "access_token") led := gpio.NewLedDriver(sparkCore, "led", "D7") diff --git a/examples/spark_core_led_brithgness.go b/examples/spark_core_led_brithgness.go index 6d92dc7cd..2082aaea3 100644 --- a/examples/spark_core_led_brithgness.go +++ b/examples/spark_core_led_brithgness.go @@ -15,13 +15,13 @@ func main() { work := func() { brightness := uint8(0) - fade_amount := uint8(25) + fadeAmount := uint8(25) gobot.Every(500*time.Millisecond, func() { led.Brightness(brightness) - brightness = brightness + fade_amount + brightness = brightness + fadeAmount if brightness == 0 || brightness == 255 { - fade_amount = -fade_amount + fadeAmount = -fadeAmount } }) } diff --git a/examples/sphero_api.go b/examples/sphero_api.go index 8ffe00f20..881dd6312 100644 --- a/examples/sphero_api.go +++ b/examples/sphero_api.go @@ -16,7 +16,7 @@ func TurnBlue(params map[string]interface{}) bool { func main() { Master = gobot.NewGobot() - api.NewApi(Master).Start() + api.NewAPI(Master).Start() spheros := map[string]string{ "Sphero-BPO": "/dev/rfcomm0", diff --git a/examples/sphero_conways.go b/examples/sphero_conways.go index f85d6405a..20573f7cb 100644 --- a/examples/sphero_conways.go +++ b/examples/sphero_conways.go @@ -64,7 +64,7 @@ func (c *conway) resetContacts() { } func (c *conway) contact() { - c.contacts += 1 + c.contacts++ } func (c *conway) rebirth() { @@ -94,13 +94,12 @@ func (c *conway) death() { func (c *conway) enoughContacts() bool { if c.contacts >= 2 && c.contacts < 7 { return true - } else { - return false } + return false } func (c *conway) birthday() { - c.age += 1 + c.age++ fmt.Println("Happy birthday", c.cell.Name, "you are", c.age, "and had", c.contacts, "contacts.") diff --git a/gobot/generate.go b/gobot/generate.go index 0d3a1074d..5ccb6d553 100644 --- a/gobot/generate.go +++ b/gobot/generate.go @@ -38,9 +38,9 @@ func Generate() cli.Command { name := generate{UpperName: upperName, Name: string(args[0]), FirstLetter: string(args[0][0])} adaptor, _ := template.New("").Parse(adaptor()) - file_location := fmt.Sprintf("%s/%s_adaptor.go", dir, args[0]) - fmt.Println("Creating", file_location) - f, err := os.Create(file_location) + fileLocation := fmt.Sprintf("%s/%s_adaptor.go", dir, args[0]) + fmt.Println("Creating", fileLocation) + f, err := os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil @@ -49,9 +49,9 @@ func Generate() cli.Command { f.Close() driver, _ := template.New("").Parse(driver()) - file_location = fmt.Sprintf("%s/%s_driver.go", dir, args[0]) - fmt.Println("Creating", file_location) - f, err = os.Create(file_location) + fileLocation = fmt.Sprintf("%s/%s_driver.go", dir, args[0]) + fmt.Println("Creating", fileLocation) + f, err = os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil @@ -60,9 +60,9 @@ func Generate() cli.Command { f.Close() readme, _ := template.New("").Parse(readme()) - file_location = fmt.Sprintf("%s/README.md", dir) - fmt.Println("Creating", file_location) - f, err = os.Create(file_location) + fileLocation = fmt.Sprintf("%s/README.md", dir) + fmt.Println("Creating", fileLocation) + f, err = os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil @@ -70,9 +70,9 @@ func Generate() cli.Command { readme.Execute(f, name) f.Close() - file_location = fmt.Sprintf("%s/LICENSE", dir) - fmt.Println("Creating", file_location) - f, err = os.Create(file_location) + fileLocation = fmt.Sprintf("%s/LICENSE", dir) + fmt.Println("Creating", fileLocation) + f, err = os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil @@ -80,9 +80,9 @@ func Generate() cli.Command { f.Close() driverTest, _ := template.New("").Parse(driverTest()) - file_location = fmt.Sprintf("%s/%s_driver_test.go", dir, args[0]) - fmt.Println("Creating", file_location) - f, err = os.Create(file_location) + fileLocation = fmt.Sprintf("%s/%s_driver_test.go", dir, args[0]) + fmt.Println("Creating", fileLocation) + f, err = os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil @@ -91,9 +91,9 @@ func Generate() cli.Command { f.Close() adaptorTest, _ := template.New("").Parse(adaptorTest()) - file_location = fmt.Sprintf("%s/%s_adaptor_test.go", dir, args[0]) - fmt.Println("Creating", file_location) - f, err = os.Create(file_location) + fileLocation = fmt.Sprintf("%s/%s_adaptor_test.go", dir, args[0]) + fmt.Println("Creating", fileLocation) + f, err = os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil @@ -102,9 +102,9 @@ func Generate() cli.Command { f.Close() testSuite, _ := template.New("").Parse(testSuite()) - file_location = fmt.Sprintf("%s/%s_suite_test.go", dir, args[0]) - fmt.Println("Creating", file_location) - f, err = os.Create(file_location) + fileLocation = fmt.Sprintf("%s/%s_suite_test.go", dir, args[0]) + fmt.Println("Creating", fileLocation) + f, err = os.Create(fileLocation) if err != nil { fmt.Println(err) err = nil diff --git a/platforms/ardrone/ardrone_adaptor.go b/platforms/ardrone/ardrone_adaptor.go index d9189c4c6..57ae15a07 100644 --- a/platforms/ardrone/ardrone_adaptor.go +++ b/platforms/ardrone/ardrone_adaptor.go @@ -45,6 +45,6 @@ func (a *ArdroneAdaptor) Finalize() bool { return true } -func (me *ArdroneAdaptor) Drone() drone { - return me.drone +func (a *ArdroneAdaptor) Drone() drone { + return a.drone } diff --git a/platforms/ardrone/ardrone_driver.go b/platforms/ardrone/ardrone_driver.go index 6a120032e..151873601 100644 --- a/platforms/ardrone/ardrone_driver.go +++ b/platforms/ardrone/ardrone_driver.go @@ -25,46 +25,46 @@ func NewArdroneDriver(adaptor DroneInterface, name string) *ArdroneDriver { } } -func (me *ArdroneDriver) Start() bool { +func (a *ArdroneDriver) Start() bool { return true } -func (me *ArdroneDriver) Halt() bool { +func (a *ArdroneDriver) Halt() bool { return true } -func (me *ArdroneDriver) Init() bool { +func (a *ArdroneDriver) Init() bool { return true } -func (me *ArdroneDriver) TakeOff() { - gobot.Publish(me.Events["Flying"], gobot.Call(me.Adaptor.Drone(), "Takeoff")) +func (a *ArdroneDriver) TakeOff() { + gobot.Publish(a.Events["Flying"], gobot.Call(a.Adaptor.Drone(), "Takeoff")) } -func (me *ArdroneDriver) Land() { - gobot.Call(me.Adaptor.Drone(), "Land") +func (a *ArdroneDriver) Land() { + gobot.Call(a.Adaptor.Drone(), "Land") } -func (me *ArdroneDriver) Up(a float64) { - gobot.Call(me.Adaptor.Drone(), "Up", a) +func (a *ArdroneDriver) Up(n float64) { + gobot.Call(a.Adaptor.Drone(), "Up", n) } -func (me *ArdroneDriver) Down(a float64) { - gobot.Call(me.Adaptor.Drone(), "Down", a) +func (a *ArdroneDriver) Down(n float64) { + gobot.Call(a.Adaptor.Drone(), "Down", n) } -func (me *ArdroneDriver) Left(a float64) { - gobot.Call(me.Adaptor.Drone(), "Left", a) +func (a *ArdroneDriver) Left(n float64) { + gobot.Call(a.Adaptor.Drone(), "Left", n) } -func (me *ArdroneDriver) Right(a float64) { - gobot.Call(me.Adaptor.Drone(), "Right", a) +func (a *ArdroneDriver) Right(n float64) { + gobot.Call(a.Adaptor.Drone(), "Right", n) } -func (me *ArdroneDriver) Forward(a float64) { - gobot.Call(me.Adaptor.Drone(), "Forward", a) +func (a *ArdroneDriver) Forward(n float64) { + gobot.Call(a.Adaptor.Drone(), "Forward", n) } -func (me *ArdroneDriver) Backward(a float64) { - gobot.Call(me.Adaptor.Drone(), "Backward", a) +func (a *ArdroneDriver) Backward(n float64) { + gobot.Call(a.Adaptor.Drone(), "Backward", n) } -func (me *ArdroneDriver) Clockwise(a float64) { - gobot.Call(me.Adaptor.Drone(), "Clockwise", a) +func (a *ArdroneDriver) Clockwise(n float64) { + gobot.Call(a.Adaptor.Drone(), "Clockwise", n) } -func (me *ArdroneDriver) CounterClockwise(a float64) { - gobot.Call(me.Adaptor.Drone(), "Counterclockwise", a) +func (a *ArdroneDriver) CounterClockwise(n float64) { + gobot.Call(a.Adaptor.Drone(), "Counterclockwise", n) } -func (me *ArdroneDriver) Hover() { - gobot.Call(me.Adaptor.Drone(), "Hover") +func (a *ArdroneDriver) Hover() { + gobot.Call(a.Adaptor.Drone(), "Hover") } diff --git a/platforms/ardrone/test_helper.go b/platforms/ardrone/test_helper.go index 5a499aee5..1cca2c0ed 100644 --- a/platforms/ardrone/test_helper.go +++ b/platforms/ardrone/test_helper.go @@ -2,14 +2,14 @@ package ardrone type testDrone struct{} -func (me testDrone) Takeoff() bool { return true } -func (me testDrone) Land() {} -func (me testDrone) Up(a float64) {} -func (me testDrone) Down(a float64) {} -func (me testDrone) Left(a float64) {} -func (me testDrone) Right(a float64) {} -func (me testDrone) Forward(a float64) {} -func (me testDrone) Backward(a float64) {} -func (me testDrone) Clockwise(a float64) {} -func (me testDrone) Counterclockwise(a float64) {} -func (me testDrone) Hover() {} +func (t testDrone) Takeoff() bool { return true } +func (t testDrone) Land() {} +func (t testDrone) Up(a float64) {} +func (t testDrone) Down(a float64) {} +func (t testDrone) Left(a float64) {} +func (t testDrone) Right(a float64) {} +func (t testDrone) Forward(a float64) {} +func (t testDrone) Backward(a float64) {} +func (t testDrone) Clockwise(a float64) {} +func (t testDrone) Counterclockwise(a float64) {} +func (t testDrone) Hover() {} diff --git a/platforms/beaglebone/analog_pin.go b/platforms/beaglebone/analog_pin.go index f6950dd59..adbc3168b 100644 --- a/platforms/beaglebone/analog_pin.go +++ b/platforms/beaglebone/analog_pin.go @@ -19,7 +19,7 @@ func newAnalogPin(pinNum string) *analogPin { d := new(analogPin) d.pinNum = pinNum - slot, err := filepath.Glob(SLOTS) + slot, err := filepath.Glob(Slots) if err != nil { panic(err) } @@ -32,11 +32,11 @@ func newAnalogPin(pinNum string) *analogPin { return d } -func (me *analogPin) analogRead() int { +func (a *analogPin) analogRead() int { var err error var fi *os.File - ocp, err := filepath.Glob(OCP) + ocp, err := filepath.Glob(Ocp) if err != nil { panic(err) } @@ -46,12 +46,12 @@ func (me *analogPin) analogRead() int { panic(err) } - fi, err = os.Open(fmt.Sprintf("%v/%v", helper[0], me.pinNum)) + fi, err = os.Open(fmt.Sprintf("%v/%v", helper[0], a.pinNum)) if err != nil { panic(err) } - var buf []byte = make([]byte, 1024) + var buf = make([]byte, 1024) fi.Read(buf) fi.Close() diff --git a/platforms/beaglebone/beaglebone_adaptor.go b/platforms/beaglebone/beaglebone_adaptor.go index a599afbd5..5b3893bea 100644 --- a/platforms/beaglebone/beaglebone_adaptor.go +++ b/platforms/beaglebone/beaglebone_adaptor.go @@ -5,9 +5,9 @@ import ( "strconv" ) -const SLOTS = "/sys/devices/bone_capemgr.*" -const OCP = "/sys/devices/ocp.*" -const I2C_LOCATION = "/dev/i2c-1" +const Slots = "/sys/devices/bone_capemgr.*" +const Ocp = "/sys/devices/ocp.*" +const I2CLocation = "/dev/i2c-1" var pins = map[string]int{ "P8_3": 38, @@ -165,7 +165,7 @@ func (b *BeagleboneAdaptor) AnalogRead(pin string) int { } func (b *BeagleboneAdaptor) I2cStart(address byte) { - b.i2cDevice = newI2cDevice(I2C_LOCATION, address) + b.i2cDevice = newI2cDevice(I2CLocation, address) b.i2cDevice.start() } diff --git a/platforms/beaglebone/digital_pin.go b/platforms/beaglebone/digital_pin.go index 5449cdffe..378976049 100644 --- a/platforms/beaglebone/digital_pin.go +++ b/platforms/beaglebone/digital_pin.go @@ -12,9 +12,9 @@ type digitalPin struct { Status string } -const GPIO_PATH = "/sys/class/gpio" -const GPIO_DIRECTION_READ = "in" -const GPIO_DIRECTION_WRITE = "out" +const GPIOPath = "/sys/class/gpio" +const GPIODirectionRead = "in" +const GPIODirectionWrite = "out" const HIGH = 1 const LOW = 0 @@ -22,7 +22,7 @@ func newDigitalPin(pinNum int, mode string) *digitalPin { d := new(digitalPin) d.PinNum = strconv.Itoa(pinNum) - fi, err := os.OpenFile(GPIO_PATH+"/export", os.O_WRONLY|os.O_APPEND, 0666) + fi, err := os.OpenFile(GPIOPath+"/export", os.O_WRONLY|os.O_APPEND, 0666) if err != nil { panic(err) } @@ -38,24 +38,24 @@ func (d *digitalPin) setMode(mode string) { d.Mode = mode if mode == "w" { - fi, err := os.OpenFile(GPIO_PATH+"/gpio"+d.PinNum+"/direction", os.O_WRONLY, 0666) + fi, err := os.OpenFile(GPIOPath+"/gpio"+d.PinNum+"/direction", os.O_WRONLY, 0666) if err != nil { panic(err) } - fi.WriteString(GPIO_DIRECTION_WRITE) + fi.WriteString(GPIODirectionWrite) fi.Close() - d.PinFile, err = os.OpenFile(GPIO_PATH+"/gpio"+d.PinNum+"/value", os.O_WRONLY, 0666) + d.PinFile, err = os.OpenFile(GPIOPath+"/gpio"+d.PinNum+"/value", os.O_WRONLY, 0666) if err != nil { panic(err) } } else if mode == "r" { - fi, err := os.OpenFile(GPIO_PATH+"/gpio"+d.PinNum+"/direction", os.O_WRONLY, 0666) + fi, err := os.OpenFile(GPIOPath+"/gpio"+d.PinNum+"/direction", os.O_WRONLY, 0666) if err != nil { panic(err) } - fi.WriteString(GPIO_DIRECTION_READ) + fi.WriteString(GPIODirectionRead) fi.Close() - d.PinFile, err = os.OpenFile(GPIO_PATH+"/gpio"+d.PinNum+"/value", os.O_RDONLY, 0666) + d.PinFile, err = os.OpenFile(GPIOPath+"/gpio"+d.PinNum+"/value", os.O_RDONLY, 0666) if err != nil { panic(err) } @@ -72,7 +72,7 @@ func (d *digitalPin) digitalWrite(value string) { } func (d *digitalPin) close() { - fi, err := os.OpenFile(GPIO_PATH+"/unexport", os.O_WRONLY|os.O_APPEND, 0666) + fi, err := os.OpenFile(GPIOPath+"/unexport", os.O_WRONLY|os.O_APPEND, 0666) if err != nil { panic(err) } diff --git a/platforms/beaglebone/i2c_device.go b/platforms/beaglebone/i2c_device.go index f904b67ec..8dee6be52 100644 --- a/platforms/beaglebone/i2c_device.go +++ b/platforms/beaglebone/i2c_device.go @@ -5,7 +5,7 @@ import ( "syscall" ) -const I2C_SLAVE = 0x0703 +const I2CSlave = 0x0703 type i2cDevice struct { i2cDevice *os.File @@ -20,26 +20,26 @@ func newI2cDevice(i2cLocation string, address byte) *i2cDevice { return d } -func (me *i2cDevice) start() { +func (i *i2cDevice) start() { var err error - me.i2cDevice, err = os.OpenFile(me.i2cLocation, os.O_RDWR, os.ModeExclusive) + i.i2cDevice, err = os.OpenFile(i.i2cLocation, os.O_RDWR, os.ModeExclusive) if err != nil { panic(err) } - _, _, errCode := syscall.Syscall(syscall.SYS_IOCTL, me.i2cDevice.Fd(), I2C_SLAVE, uintptr(me.address)) + _, _, errCode := syscall.Syscall(syscall.SYS_IOCTL, i.i2cDevice.Fd(), I2CSlave, uintptr(i.address)) if errCode != 0 { panic(err) } - me.write([]byte{0}) + i.write([]byte{0}) } -func (me *i2cDevice) write(data []byte) { - me.i2cDevice.Write(data) +func (i *i2cDevice) write(data []byte) { + i.i2cDevice.Write(data) } -func (me *i2cDevice) read(len uint) []byte { +func (i *i2cDevice) read(len uint) []byte { buf := make([]byte, len) - me.i2cDevice.Read(buf) + i.i2cDevice.Read(buf) return buf } diff --git a/platforms/beaglebone/pwm_pin.go b/platforms/beaglebone/pwm_pin.go index 56e0c06c2..7ac12d249 100644 --- a/platforms/beaglebone/pwm_pin.go +++ b/platforms/beaglebone/pwm_pin.go @@ -19,7 +19,7 @@ func newPwmPin(pinNum string) *pwmPin { d := new(pwmPin) d.pinNum = strings.ToUpper(pinNum) - slots, err := filepath.Glob(SLOTS) + slots, err := filepath.Glob(Slots) if err != nil { panic(err) } @@ -33,7 +33,7 @@ func newPwmPin(pinNum string) *pwmPin { fi.Sync() fi.Close() - ocp, err := filepath.Glob(OCP) + ocp, err := filepath.Glob(Ocp) if err != nil { panic(err) } @@ -57,18 +57,18 @@ func newPwmPin(pinNum string) *pwmPin { return d } -func (me *pwmPin) pwmWrite(period string, duty string) { +func (p *pwmPin) pwmWrite(period string, duty string) { var err error var fi *os.File - fi, err = os.OpenFile(fmt.Sprintf("%v/period", me.pwmDevice), os.O_WRONLY|os.O_APPEND, 0666) + fi, err = os.OpenFile(fmt.Sprintf("%v/period", p.pwmDevice), os.O_WRONLY|os.O_APPEND, 0666) if err != nil { panic(err) } fi.WriteString(period) fi.Close() - fi, err = os.OpenFile(fmt.Sprintf("%v/duty", me.pwmDevice), os.O_WRONLY|os.O_APPEND, 0666) + fi, err = os.OpenFile(fmt.Sprintf("%v/duty", p.pwmDevice), os.O_WRONLY|os.O_APPEND, 0666) if err != nil { panic(err) } @@ -76,8 +76,8 @@ func (me *pwmPin) pwmWrite(period string, duty string) { fi.Close() } -func (me *pwmPin) release() { - fi, err := os.OpenFile(fmt.Sprintf("%v/run", me.pwmDevice), os.O_WRONLY|os.O_APPEND, 0666) +func (p *pwmPin) release() { + fi, err := os.OpenFile(fmt.Sprintf("%v/run", p.pwmDevice), os.O_WRONLY|os.O_APPEND, 0666) if err != nil { panic(err) } diff --git a/platforms/firmata/firmata.go b/platforms/firmata/firmata.go index 53b6a5648..2f9443563 100644 --- a/platforms/firmata/firmata.go +++ b/platforms/firmata/firmata.go @@ -9,43 +9,43 @@ import ( ) const ( - OPEN byte = 1 - CLOSE byte = 0 - INPUT byte = 0x00 - OUTPUT byte = 0x01 - ANALOG byte = 0x02 - PWM byte = 0x03 - SERVO byte = 0x04 - LOW byte = 0 - HIGH byte = 1 - REPORT_VERSION byte = 0xF9 - SYSTEM_RESET byte = 0xFF - DIGITAL_MESSAGE byte = 0x90 - DIGITAL_MESSAGE_RANGE_START byte = 0x90 - DIGITAL_MESSAGE_RANGE_END byte = 0x9F - ANALOG_MESSAGE byte = 0xE0 - ANALOG_MESSAGE_RANGE_START byte = 0xE0 - ANALOG_MESSAGE_RANGE_END byte = 0xEF - REPORT_ANALOG byte = 0xC0 - REPORT_DIGITAL byte = 0xD0 - PIN_MODE byte = 0xF4 - START_SYSEX byte = 0xF0 - END_SYSEX byte = 0xF7 - CAPABILITY_QUERY byte = 0x6B - CAPABILITY_RESPONSE byte = 0x6C - PIN_STATE_QUERY byte = 0x6D - PIN_STATE_RESPONSE byte = 0x6E - ANALOG_MAPPING_QUERY byte = 0x69 - ANALOG_MAPPING_RESPONSE byte = 0x6A - STRING_DATA byte = 0x71 - I2C_REQUEST byte = 0x76 - I2C_REPLY byte = 0x77 - I2C_CONFIG byte = 0x78 - FIRMWARE_QUERY byte = 0x79 - I2C_MODE_WRITE byte = 0x00 - I2C_MODE_READ byte = 0x01 - I2C_MODE_CONTINUOUS_READ byte = 0x02 - I2C_MODE_STOP_READING byte = 0x03 + Open byte = 1 + Close byte = 0 + Input byte = 0x00 + Output byte = 0x01 + Analog byte = 0x02 + PWM byte = 0x03 + Servo byte = 0x04 + Low byte = 0 + High byte = 1 + ReportVersion byte = 0xF9 + SystemReset byte = 0xFF + DigitalMessage byte = 0x90 + DigitalMessageRangeStart byte = 0x90 + DigitalMessageRangeEnd byte = 0x9F + AnalogMessage byte = 0xE0 + AnalogMessageRangeStart byte = 0xE0 + AnalogMessageRangeEnd byte = 0xEF + ReportAnalog byte = 0xC0 + ReportDigital byte = 0xD0 + PinMode byte = 0xF4 + StartSysex byte = 0xF0 + EndSysex byte = 0xF7 + CapabilityQuery byte = 0x6B + CapabilityResponse byte = 0x6C + PinStateQuery byte = 0x6D + PinStateResponse byte = 0x6E + AnalogMappingQuery byte = 0x69 + AnalogMappingResponse byte = 0x6A + StringData byte = 0x71 + I2CRequest byte = 0x76 + I2CReply byte = 0x77 + I2CConfig byte = 0x78 + FirmwareQuery byte = 0x79 + I2CModeWrite byte = 0x00 + I2CModeRead byte = 0x01 + I2CmodeContinuousRead byte = 0x02 + I2CModeStopReading byte = 0x03 ) type board struct { @@ -125,14 +125,14 @@ func (b *board) initBoard() { break } } - b.togglePinReporting(0, HIGH, REPORT_DIGITAL) + b.togglePinReporting(0, High, ReportDigital) time.Sleep(50 * time.Millisecond) - b.togglePinReporting(1, HIGH, REPORT_DIGITAL) + b.togglePinReporting(1, High, ReportDigital) time.Sleep(50 * time.Millisecond) } func (b *board) findEvents(name string) []event { - ret := make([]event, 0) + ret := []event{} for key, val := range b.Events { if val.Name == name { ret = append(ret, val) @@ -149,12 +149,12 @@ func (b *board) readAndProcess() { } func (b *board) reset() { - b.write([]byte{SYSTEM_RESET}) + b.write([]byte{SystemReset}) } func (b *board) setPinMode(pin byte, mode byte) { b.Pins[pin].Mode = mode - b.write([]byte{PIN_MODE, pin, mode}) + b.write([]byte{PinMode, pin, mode}) } func (b *board) digitalWrite(pin byte, value byte) { @@ -168,12 +168,12 @@ func (b *board) digitalWrite(pin byte, value byte) { portValue = portValue | (1 << i) } } - b.write([]byte{DIGITAL_MESSAGE | port, portValue & 0x7F, (portValue >> 7) & 0x7F}) + b.write([]byte{DigitalMessage | port, portValue & 0x7F, (portValue >> 7) & 0x7F}) } func (b *board) analogWrite(pin byte, value byte) { b.Pins[pin].Value = int(value) - b.write([]byte{ANALOG_MESSAGE | pin, value & 0x7F, (value >> 7) & 0x7F}) + b.write([]byte{AnalogMessage | pin, value & 0x7F, (value >> 7) & 0x7F}) } func (b *board) version() string { @@ -181,54 +181,54 @@ func (b *board) version() string { } func (b *board) reportVersion() { - b.write([]byte{REPORT_VERSION}) + b.write([]byte{ReportVersion}) } func (b *board) queryFirmware() { - b.write([]byte{START_SYSEX, FIRMWARE_QUERY, END_SYSEX}) + b.write([]byte{StartSysex, FirmwareQuery, EndSysex}) } func (b *board) queryPinState(pin byte) { - b.write([]byte{START_SYSEX, PIN_STATE_QUERY, pin, END_SYSEX}) + b.write([]byte{StartSysex, PinStateQuery, pin, EndSysex}) } func (b *board) queryReportVersion() { - b.write([]byte{REPORT_VERSION}) + b.write([]byte{ReportVersion}) } func (b *board) queryCapabilities() { - b.write([]byte{START_SYSEX, CAPABILITY_QUERY, END_SYSEX}) + b.write([]byte{StartSysex, CapabilityQuery, EndSysex}) } func (b *board) queryAnalogMapping() { - b.write([]byte{START_SYSEX, ANALOG_MAPPING_QUERY, END_SYSEX}) + b.write([]byte{StartSysex, AnalogMappingQuery, EndSysex}) } func (b *board) togglePinReporting(pin byte, state byte, mode byte) { b.write([]byte{mode | pin, state}) } -func (b *board) i2cReadRequest(slave_address byte, num_bytes uint) { - b.write([]byte{START_SYSEX, I2C_REQUEST, slave_address, (I2C_MODE_READ << 3), byte(num_bytes & 0x7F), byte(((num_bytes >> 7) & 0x7F)), END_SYSEX}) +func (b *board) i2cReadRequest(slaveAddress byte, numBytes uint) { + b.write([]byte{StartSysex, I2CRequest, slaveAddress, (I2CModeRead << 3), byte(numBytes & 0x7F), byte(((numBytes >> 7) & 0x7F)), EndSysex}) } -func (b *board) i2cWriteRequest(slave_address byte, data []byte) { - ret := []byte{START_SYSEX, I2C_REQUEST, slave_address, (I2C_MODE_WRITE << 3)} +func (b *board) i2cWriteRequest(slaveAddress byte, data []byte) { + ret := []byte{StartSysex, I2CRequest, slaveAddress, (I2CModeWrite << 3)} for _, val := range data { ret = append(ret, byte(val&0x7F)) ret = append(ret, byte((val>>7)&0x7F)) } - ret = append(ret, END_SYSEX) + ret = append(ret, EndSysex) b.write(ret) } func (b *board) i2cConfig(data []byte) { - ret := []byte{START_SYSEX, I2C_CONFIG} + ret := []byte{StartSysex, I2CConfig} for _, val := range data { ret = append(ret, byte(val&0xFF)) ret = append(ret, byte((val>>8)&0xFF)) } - ret = append(ret, END_SYSEX) + ret = append(ret, EndSysex) b.write(ret) } @@ -242,141 +242,141 @@ func (b *board) read() []byte { return buf } -func (me *board) process(data []byte) { +func (b *board) process(data []byte) { buf := bytes.NewBuffer(data) for { - b, err := buf.ReadByte() + messageType, err := buf.ReadByte() if err != nil { break } - switch b { - case REPORT_VERSION: - me.MajorVersion, _ = buf.ReadByte() - me.MinorVersion, _ = buf.ReadByte() - me.Events = append(me.Events, event{Name: "report_version"}) - case ANALOG_MESSAGE: - least_significant_byte, _ := buf.ReadByte() - most_significant_byte, _ := buf.ReadByte() - - value := uint(least_significant_byte) | uint(most_significant_byte)<<7 - pin := (b & 0x0F) - - me.Pins[me.AnalogPins[pin]].Value = int(value) - me.Events = append(me.Events, event{Name: fmt.Sprintf("analog_read_%v", pin), Data: []byte{byte(value >> 24), byte(value >> 16), byte(value >> 8), byte(value & 0xff)}}) - - case DIGITAL_MESSAGE: - port := b & 0x0F - first_bitmask, _ := buf.ReadByte() - second_bitmask, _ := buf.ReadByte() - port_value := first_bitmask | (second_bitmask << 7) + switch messageType { + case ReportVersion: + b.MajorVersion, _ = buf.ReadByte() + b.MinorVersion, _ = buf.ReadByte() + b.Events = append(b.Events, event{Name: "report_version"}) + case AnalogMessage: + leastSignificantByte, _ := buf.ReadByte() + mostSignificantByte, _ := buf.ReadByte() + + value := uint(leastSignificantByte) | uint(mostSignificantByte)<<7 + pin := (messageType & 0x0F) + + b.Pins[b.AnalogPins[pin]].Value = int(value) + b.Events = append(b.Events, event{Name: fmt.Sprintf("analog_read_%v", pin), Data: []byte{byte(value >> 24), byte(value >> 16), byte(value >> 8), byte(value & 0xff)}}) + + case DigitalMessage: + port := messageType & 0x0F + firstBitmask, _ := buf.ReadByte() + secondBitmask, _ := buf.ReadByte() + portValue := firstBitmask | (secondBitmask << 7) for i := 0; i < 8; i++ { - pin_number := (8*byte(port) + byte(i)) - pin := me.Pins[pin_number] - if byte(pin.Mode) == INPUT { - pin.Value = int((port_value >> (byte(i) & 0x07)) & 0x01) - me.Events = append(me.Events, event{Name: fmt.Sprintf("digital_read_%v", pin_number), Data: []byte{byte(pin.Value & 0xff)}}) + pinNumber := (8*byte(port) + byte(i)) + pin := b.Pins[pinNumber] + if byte(pin.Mode) == Input { + pin.Value = int((portValue >> (byte(i) & 0x07)) & 0x01) + b.Events = append(b.Events, event{Name: fmt.Sprintf("digital_read_%v", pinNumber), Data: []byte{byte(pin.Value & 0xff)}}) } } - case START_SYSEX: - current_buffer := []byte{b} + case StartSysex: + currentBuffer := []byte{messageType} for { b, err := buf.ReadByte() if err != nil { break } - current_buffer = append(current_buffer, b) - if current_buffer[len(current_buffer)-1] == END_SYSEX { + currentBuffer = append(currentBuffer, b) + if currentBuffer[len(currentBuffer)-1] == EndSysex { break } } - command := current_buffer[1] + command := currentBuffer[1] switch command { - case CAPABILITY_RESPONSE: - supported_modes := 0 + case CapabilityResponse: + supportedModes := 0 n := 0 - for _, val := range current_buffer[2:(len(current_buffer) - 5)] { + for _, val := range currentBuffer[2:(len(currentBuffer) - 5)] { if val == 127 { - modes := make([]byte, 0) - for _, mode := range []byte{INPUT, OUTPUT, ANALOG, PWM, SERVO} { - if (supported_modes & (1 << mode)) != 0 { + modes := []byte{} + for _, mode := range []byte{Input, Output, Analog, PWM, Servo} { + if (supportedModes & (1 << mode)) != 0 { modes = append(modes, mode) } } - me.Pins = append(me.Pins, pin{modes, OUTPUT, 0, 0}) - supported_modes = 0 + b.Pins = append(b.Pins, pin{modes, Output, 0, 0}) + supportedModes = 0 n = 0 continue } if n == 0 { - supported_modes = supported_modes | (1 << val) + supportedModes = supportedModes | (1 << val) } n ^= 1 } - me.Events = append(me.Events, event{Name: "capability_query"}) + b.Events = append(b.Events, event{Name: "capability_query"}) - case ANALOG_MAPPING_RESPONSE: - pin_index := byte(0) + case AnalogMappingResponse: + pinIndex := byte(0) - for _, val := range current_buffer[2 : len(current_buffer)-1] { + for _, val := range currentBuffer[2 : len(currentBuffer)-1] { - me.Pins[pin_index].AnalogChannel = val + b.Pins[pinIndex].AnalogChannel = val if val != 127 { - me.AnalogPins = append(me.AnalogPins, pin_index) + b.AnalogPins = append(b.AnalogPins, pinIndex) } - pin_index += 1 + pinIndex++ } - me.Events = append(me.Events, event{Name: "analog_mapping_query"}) + b.Events = append(b.Events, event{Name: "analog_mapping_query"}) - case PIN_STATE_RESPONSE: - pin := me.Pins[current_buffer[2]] - pin.Mode = current_buffer[3] - pin.Value = int(current_buffer[4]) + case PinStateResponse: + pin := b.Pins[currentBuffer[2]] + pin.Mode = currentBuffer[3] + pin.Value = int(currentBuffer[4]) - if len(current_buffer) > 6 { - pin.Value = int(uint(pin.Value) | uint(current_buffer[5])<<7) + if len(currentBuffer) > 6 { + pin.Value = int(uint(pin.Value) | uint(currentBuffer[5])<<7) } - if len(current_buffer) > 7 { - pin.Value = int(uint(pin.Value) | uint(current_buffer[6])<<14) + if len(currentBuffer) > 7 { + pin.Value = int(uint(pin.Value) | uint(currentBuffer[6])<<14) } - me.Events = append(me.Events, event{Name: fmt.Sprintf("pin_%v_state", current_buffer[2]), Data: []byte{byte(pin.Value & 0xff)}}) - case I2C_REPLY: - i2c_reply := map[string][]byte{ - "slave_address": []byte{byte(current_buffer[2]) | byte(current_buffer[3])<<7}, - "register": []byte{byte(current_buffer[4]) | byte(current_buffer[5])<<7}, - "data": []byte{byte(current_buffer[6]) | byte(current_buffer[7])<<7}, + b.Events = append(b.Events, event{Name: fmt.Sprintf("pin_%v_state", currentBuffer[2]), Data: []byte{byte(pin.Value & 0xff)}}) + case I2CReply: + i2cReply := map[string][]byte{ + "slave_address": []byte{byte(currentBuffer[2]) | byte(currentBuffer[3])<<7}, + "register": []byte{byte(currentBuffer[4]) | byte(currentBuffer[5])<<7}, + "data": []byte{byte(currentBuffer[6]) | byte(currentBuffer[7])<<7}, } - for i := 8; i < len(current_buffer); i = i + 2 { - if current_buffer[i] == byte(0xF7) { + for i := 8; i < len(currentBuffer); i = i + 2 { + if currentBuffer[i] == byte(0xF7) { break } - if i+2 > len(current_buffer) { + if i+2 > len(currentBuffer) { break } - i2c_reply["data"] = append(i2c_reply["data"], byte(current_buffer[i])|byte(current_buffer[i+1])<<7) + i2cReply["data"] = append(i2cReply["data"], byte(currentBuffer[i])|byte(currentBuffer[i+1])<<7) } - me.Events = append(me.Events, event{Name: "i2c_reply", I2cReply: i2c_reply}) + b.Events = append(b.Events, event{Name: "i2c_reply", I2cReply: i2cReply}) - case FIRMWARE_QUERY: - name := make([]byte, 0) - for _, val := range current_buffer[4:(len(current_buffer) - 1)] { + case FirmwareQuery: + name := []byte{} + for _, val := range currentBuffer[4:(len(currentBuffer) - 1)] { if val != 0 { name = append(name, val) } } - me.FirmwareName = string(name[:]) - me.Events = append(me.Events, event{Name: "firmware_query"}) - case STRING_DATA: - str := current_buffer[2 : len(current_buffer)-1] + b.FirmwareName = string(name[:]) + b.Events = append(b.Events, event{Name: "firmware_query"}) + case StringData: + str := currentBuffer[2 : len(currentBuffer)-1] fmt.Println(string(str[:len(str)])) - me.Events = append(me.Events, event{Name: "string_data", Data: str}) + b.Events = append(b.Events, event{Name: "string_data", Data: str}) default: fmt.Println("bad byte", fmt.Sprintf("0x%x", command)) } diff --git a/platforms/firmata/firmata_adaptor.go b/platforms/firmata/firmata_adaptor.go index 8400b735c..eece47a96 100644 --- a/platforms/firmata/firmata_adaptor.go +++ b/platforms/firmata/firmata_adaptor.go @@ -50,7 +50,7 @@ func (f *FirmataAdaptor) InitServo() {} func (f *FirmataAdaptor) ServoWrite(pin string, angle byte) { p, _ := strconv.Atoi(pin) - f.Board.setPinMode(byte(p), SERVO) + f.Board.setPinMode(byte(p), Servo) f.Board.analogWrite(byte(p), angle) } @@ -64,14 +64,14 @@ func (f *FirmataAdaptor) PwmWrite(pin string, level byte) { func (f *FirmataAdaptor) DigitalWrite(pin string, level byte) { p, _ := strconv.Atoi(pin) - f.Board.setPinMode(byte(p), OUTPUT) + f.Board.setPinMode(byte(p), Output) f.Board.digitalWrite(byte(p), level) } func (f *FirmataAdaptor) DigitalRead(pin string) int { p, _ := strconv.Atoi(pin) - f.Board.setPinMode(byte(p), INPUT) - f.Board.togglePinReporting(byte(p), HIGH, REPORT_DIGITAL) + f.Board.setPinMode(byte(p), Input) + f.Board.togglePinReporting(byte(p), High, ReportDigital) events := f.Board.findEvents(fmt.Sprintf("digital_read_%v", pin)) if len(events) > 0 { return int(events[len(events)-1].Data[0]) @@ -83,8 +83,8 @@ func (f *FirmataAdaptor) DigitalRead(pin string) int { func (f *FirmataAdaptor) AnalogRead(pin string) int { p, _ := strconv.Atoi(pin) p = f.digitalPin(p) - f.Board.setPinMode(byte(p), ANALOG) - f.Board.togglePinReporting(byte(p), HIGH, REPORT_ANALOG) + f.Board.setPinMode(byte(p), Analog) + f.Board.togglePinReporting(byte(p), High, ReportAnalog) events := f.Board.findEvents(fmt.Sprintf("analog_read_%v", pin)) if len(events) > 0 { event := events[len(events)-1] diff --git a/platforms/firmata/firmata_adaptor_test.go b/platforms/firmata/firmata_adaptor_test.go index 9fa49cb7e..aba56cf80 100644 --- a/platforms/firmata/firmata_adaptor_test.go +++ b/platforms/firmata/firmata_adaptor_test.go @@ -44,18 +44,18 @@ var _ = Describe("FirmataAdaptor", func() { Expect(adaptor.DigitalRead("1")).To(Equal(-1)) }) It("DigitalRead should return data", func() { - pin_number := "1" - adaptor.Board.Events = append(adaptor.Board.Events, event{Name: fmt.Sprintf("digital_read_%v", pin_number), Data: []byte{0x01}}) - Expect(adaptor.DigitalRead(pin_number)).To(Equal(0x01)) + pinNumber := "1" + adaptor.Board.Events = append(adaptor.Board.Events, event{Name: fmt.Sprintf("digital_read_%v", pinNumber), Data: []byte{0x01}}) + Expect(adaptor.DigitalRead(pinNumber)).To(Equal(0x01)) }) It("AnalogRead should return -1 on no data", func() { Expect(adaptor.AnalogRead("1")).To(Equal(-1)) }) It("AnalogRead should return data", func() { - pin_number := "1" + pinNumber := "1" value := 133 - adaptor.Board.Events = append(adaptor.Board.Events, event{Name: fmt.Sprintf("analog_read_%v", pin_number), Data: []byte{byte(value >> 24), byte(value >> 16), byte(value >> 8), byte(value & 0xff)}}) - Expect(adaptor.AnalogRead(pin_number)).To(Equal(133)) + adaptor.Board.Events = append(adaptor.Board.Events, event{Name: fmt.Sprintf("analog_read_%v", pinNumber), Data: []byte{byte(value >> 24), byte(value >> 16), byte(value >> 8), byte(value & 0xff)}}) + Expect(adaptor.AnalogRead(pinNumber)).To(Equal(133)) }) It("Must be able to I2cStart", func() { adaptor.I2cStart(0x00) @@ -65,9 +65,9 @@ var _ = Describe("FirmataAdaptor", func() { }) It("I2cRead should return data", func() { i := []byte{100} - i2c_reply := map[string][]byte{} - i2c_reply["data"] = i - adaptor.Board.Events = append(adaptor.Board.Events, event{Name: "i2c_reply", I2cReply: i2c_reply}) + i2cReply := map[string][]byte{} + i2cReply["data"] = i + adaptor.Board.Events = append(adaptor.Board.Events, event{Name: "i2c_reply", I2cReply: i2cReply}) Expect(adaptor.I2cRead(1)).To(Equal(i)) }) It("Must be able to I2cWrite", func() { diff --git a/platforms/gpio/button_driver.go b/platforms/gpio/button_driver.go index 022a55b07..75474e91c 100644 --- a/platforms/gpio/button_driver.go +++ b/platforms/gpio/button_driver.go @@ -28,10 +28,10 @@ func NewButtonDriver(a DigitalReader, name string, pin string) *ButtonDriver { func (b *ButtonDriver) Start() bool { state := 0 gobot.Every(b.Interval, func() { - new_value := b.readState() - if new_value != state && new_value != -1 { - state = new_value - b.update(new_value) + newValue := b.readState() + if newValue != state && newValue != -1 { + state = newValue + b.update(newValue) } }) return true @@ -43,12 +43,12 @@ func (b *ButtonDriver) readState() int { return b.Adaptor.DigitalRead(b.Pin) } -func (b *ButtonDriver) update(new_val int) { - if new_val == 1 { +func (b *ButtonDriver) update(newVal int) { + if newVal == 1 { b.Active = true - gobot.Publish(b.Events["push"], new_val) + gobot.Publish(b.Events["push"], newVal) } else { b.Active = false - gobot.Publish(b.Events["release"], new_val) + gobot.Publish(b.Events["release"], newVal) } } diff --git a/platforms/gpio/makey_button_driver.go b/platforms/gpio/makey_button_driver.go index bfc89d37d..c4313bed4 100644 --- a/platforms/gpio/makey_button_driver.go +++ b/platforms/gpio/makey_button_driver.go @@ -29,10 +29,10 @@ func NewMakeyButtonDriver(a DigitalReader, name string, pin string) *MakeyButton func (m *MakeyButtonDriver) Start() bool { state := 0 gobot.Every(m.Interval, func() { - new_value := m.readState() - if new_value != state && new_value != -1 { - state = new_value - m.update(new_value) + newValue := m.readState() + if newValue != state && newValue != -1 { + state = newValue + m.update(newValue) } }) return true @@ -44,12 +44,12 @@ func (m *MakeyButtonDriver) readState() int { return m.Adaptor.DigitalRead(m.Pin) } -func (m *MakeyButtonDriver) update(new_val int) { - if new_val == 0 { +func (m *MakeyButtonDriver) update(newVal int) { + if newVal == 0 { m.Active = true - gobot.Publish(m.Events["push"], new_val) + gobot.Publish(m.Events["push"], newVal) } else { m.Active = false - gobot.Publish(m.Events["release"], new_val) + gobot.Publish(m.Events["release"], newVal) } } diff --git a/platforms/gpio/motor_driver.go b/platforms/gpio/motor_driver.go index 91cfdd91d..3e8e076ea 100644 --- a/platforms/gpio/motor_driver.go +++ b/platforms/gpio/motor_driver.go @@ -79,9 +79,8 @@ func (m *MotorDriver) Max() { func (m *MotorDriver) IsOn() bool { if m.isDigital() { return m.CurrentState == 1 - } else { - return m.CurrentSpeed > 0 } + return m.CurrentSpeed > 0 } func (m *MotorDriver) IsOff() bool { diff --git a/platforms/i2c/hmc6352_driver.go b/platforms/i2c/hmc6352_driver.go index e8620b964..7d1683fdb 100644 --- a/platforms/i2c/hmc6352_driver.go +++ b/platforms/i2c/hmc6352_driver.go @@ -32,5 +32,5 @@ func (h *HMC6352Driver) Start() bool { }) return true } -func (self *HMC6352Driver) Init() bool { return true } -func (self *HMC6352Driver) Halt() bool { return true } +func (h *HMC6352Driver) Init() bool { return true } +func (h *HMC6352Driver) Halt() bool { return true } diff --git a/platforms/i2c/wiichuck_driver.go b/platforms/i2c/wiichuck_driver.go index 0af529973..bf8f69028 100644 --- a/platforms/i2c/wiichuck_driver.go +++ b/platforms/i2c/wiichuck_driver.go @@ -41,9 +41,9 @@ func (w *WiichuckDriver) Start() bool { gobot.Every(w.Interval, func() { w.Adaptor.I2cWrite([]byte{0x40, 0x00}) w.Adaptor.I2cWrite([]byte{0x00}) - new_value := w.Adaptor.I2cRead(6) - if len(new_value) == 6 { - w.update(new_value) + newValue := w.Adaptor.I2cRead(6) + if len(newValue) == 6 { + w.update(newValue) } }) return true @@ -62,9 +62,9 @@ func (w *WiichuckDriver) update(value []byte) { } } -func (w *WiichuckDriver) setJoystickDefaultValue(joystick_axis string, default_value float64) { - if w.joystick[joystick_axis] == -1 { - w.joystick[joystick_axis] = default_value +func (w *WiichuckDriver) setJoystickDefaultValue(joystickAxis string, defaultValue float64) { + if w.joystick[joystickAxis] == -1 { + w.joystick[joystickAxis] = defaultValue } } @@ -75,9 +75,8 @@ func (w *WiichuckDriver) calculateJoystickValue(axis float64, origin float64) fl func (w *WiichuckDriver) isEncrypted(value []byte) bool { if value[0] == value[1] && value[2] == value[3] && value[4] == value[5] { return true - } else { - return false } + return false } func (w *WiichuckDriver) decode(x byte) float64 { diff --git a/platforms/joystick/joystick_driver.go b/platforms/joystick/joystick_driver.go index ba8d3adf3..77acd5ecc 100644 --- a/platforms/joystick/joystick_driver.go +++ b/platforms/joystick/joystick_driver.go @@ -17,13 +17,13 @@ type JoystickDriver struct { type pair struct { Name string `json:"name"` - Id int `json:"id"` + ID int `json:"id"` } type hat struct { Hat int `json:"hat"` Name string `json:"name"` - Id int `json:"id"` + ID int `json:"id"` } type joystickConfig struct { @@ -111,7 +111,7 @@ func (j *JoystickDriver) Halt() bool { return true } func (j *JoystickDriver) findName(id uint8, list []pair) string { for _, value := range list { - if int(id) == value.Id { + if int(id) == value.ID { return value.Name } } @@ -120,7 +120,7 @@ func (j *JoystickDriver) findName(id uint8, list []pair) string { func (j *JoystickDriver) findHatName(id uint8, hat uint8, list []hat) string { for _, value := range list { - if int(id) == value.Id && int(hat) == value.Hat { + if int(id) == value.ID && int(hat) == value.Hat { return value.Name } } diff --git a/platforms/leap/leap_motion_adaptor.go b/platforms/leap/leap_motion_adaptor.go index 8f4bd2a3b..1d077e112 100644 --- a/platforms/leap/leap_motion_adaptor.go +++ b/platforms/leap/leap_motion_adaptor.go @@ -35,4 +35,4 @@ func (l *LeapMotionAdaptor) Connect() bool { l.Connected = true return true } -func (me *LeapMotionAdaptor) Finalize() bool { return true } +func (l *LeapMotionAdaptor) Finalize() bool { return true } diff --git a/platforms/leap/leap_motion_driver.go b/platforms/leap/leap_motion_driver.go index af2f04a7d..08c016247 100644 --- a/platforms/leap/leap_motion_driver.go +++ b/platforms/leap/leap_motion_driver.go @@ -41,5 +41,5 @@ func (l *LeapMotionDriver) Start() bool { return true } -func (me *LeapMotionDriver) Init() bool { return true } -func (me *LeapMotionDriver) Halt() bool { return true } +func (l *LeapMotionDriver) Init() bool { return true } +func (l *LeapMotionDriver) Halt() bool { return true } diff --git a/platforms/neurosky/neurosky_driver.go b/platforms/neurosky/neurosky_driver.go index 9847d7ddc..0123fe4df 100644 --- a/platforms/neurosky/neurosky_driver.go +++ b/platforms/neurosky/neurosky_driver.go @@ -5,14 +5,14 @@ import ( "github.com/hybridgroup/gobot" ) -const BT_SYNC byte = 0xAA -const CODE_EX byte = 0x55 // Extended code -const CODE_SIGNAL_QUALITY byte = 0x02 // POOR_SIGNAL quality 0-255 -const CODE_ATTENTION byte = 0x04 // ATTENTION eSense 0-100 -const CODE_MEDITATION byte = 0x05 // MEDITATION eSense 0-100 -const CODE_BLINK byte = 0x16 // BLINK strength 0-255 -const CODE_WAVE byte = 0x80 // RAW wave value: 2-byte big-endian 2s-complement -const CODE_ASIC_EEG byte = 0x83 // ASIC EEG POWER 8 3-byte big-endian integers +const BTSync byte = 0xAA +const CodeEx byte = 0x55 // Extended code +const CodeSignalQuality byte = 0x02 // POOR_SIGNAL quality 0-255 +const CodeAttention byte = 0x04 // ATTENTION eSense 0-100 +const CodeMeditation byte = 0x05 // MEDITATION eSense 0-100 +const CodeBlink byte = 0x16 // BLINK strength 0-255 +const CodeWave byte = 0x80 // RAW wave value: 2-byte big-endian 2s-complement +const CodeAsicEEG byte = 0x83 // ASIC EEG POWER 8 3-byte big-endian integers type NeuroskyDriver struct { gobot.Driver @@ -69,7 +69,7 @@ func (n *NeuroskyDriver) parse(buf *bytes.Buffer) { for buf.Len() > 2 { b1, _ := buf.ReadByte() b2, _ := buf.ReadByte() - if b1 == BT_SYNC && b2 == BT_SYNC { + if b1 == BTSync && b2 == BTSync { length, _ := buf.ReadByte() var payload = make([]byte, int(length)) buf.Read(payload) @@ -80,53 +80,53 @@ func (n *NeuroskyDriver) parse(buf *bytes.Buffer) { } } -func (me *NeuroskyDriver) parsePacket(data []byte) { +func (n *NeuroskyDriver) parsePacket(data []byte) { buf := bytes.NewBuffer(data) for buf.Len() > 0 { b, _ := buf.ReadByte() switch b { - case CODE_EX: - gobot.Publish(me.Events["Extended"], nil) - case CODE_SIGNAL_QUALITY: + case CodeEx: + gobot.Publish(n.Events["Extended"], nil) + case CodeSignalQuality: ret, _ := buf.ReadByte() - gobot.Publish(me.Events["Signal"], ret) - case CODE_ATTENTION: + gobot.Publish(n.Events["Signal"], ret) + case CodeAttention: ret, _ := buf.ReadByte() - gobot.Publish(me.Events["Attention"], ret) - case CODE_MEDITATION: + gobot.Publish(n.Events["Attention"], ret) + case CodeMeditation: ret, _ := buf.ReadByte() - gobot.Publish(me.Events["Meditation"], ret) - case CODE_BLINK: + gobot.Publish(n.Events["Meditation"], ret) + case CodeBlink: ret, _ := buf.ReadByte() - gobot.Publish(me.Events["Blink"], ret) - case CODE_WAVE: + gobot.Publish(n.Events["Blink"], ret) + case CodeWave: buf.Next(1) var ret = make([]byte, 2) buf.Read(ret) - gobot.Publish(me.Events["Wave"], ret) - case CODE_ASIC_EEG: + gobot.Publish(n.Events["Wave"], ret) + case CodeAsicEEG: var ret = make([]byte, 25) - n, _ := buf.Read(ret) - if n == 25 { - gobot.Publish(me.Events["EEG"], me.parseEEG(ret)) + i, _ := buf.Read(ret) + if i == 25 { + gobot.Publish(n.Events["EEG"], n.parseEEG(ret)) } } } } -func (me *NeuroskyDriver) parseEEG(data []byte) EEG { +func (n *NeuroskyDriver) parseEEG(data []byte) EEG { return EEG{ - Delta: me.parse3ByteInteger(data[0:3]), - Theta: me.parse3ByteInteger(data[3:6]), - LoAlpha: me.parse3ByteInteger(data[6:9]), - HiAlpha: me.parse3ByteInteger(data[9:12]), - LoBeta: me.parse3ByteInteger(data[12:15]), - HiBeta: me.parse3ByteInteger(data[15:18]), - LoGamma: me.parse3ByteInteger(data[18:21]), - MidGamma: me.parse3ByteInteger(data[21:25]), + Delta: n.parse3ByteInteger(data[0:3]), + Theta: n.parse3ByteInteger(data[3:6]), + LoAlpha: n.parse3ByteInteger(data[6:9]), + HiAlpha: n.parse3ByteInteger(data[9:12]), + LoBeta: n.parse3ByteInteger(data[12:15]), + HiBeta: n.parse3ByteInteger(data[15:18]), + LoGamma: n.parse3ByteInteger(data[18:21]), + MidGamma: n.parse3ByteInteger(data[21:25]), } } -func (me *NeuroskyDriver) parse3ByteInteger(data []byte) int { +func (n *NeuroskyDriver) parse3ByteInteger(data []byte) int { return ((int(data[0]) << 16) | (((1 << 16) - 1) & (int(data[1]) << 8)) | (((1 << 8) - 1) & int(data[2]))) } diff --git a/platforms/pebble/README.md b/platforms/pebble/README.md index 9b8a71121..4f9557016 100644 --- a/platforms/pebble/README.md +++ b/platforms/pebble/README.md @@ -37,7 +37,7 @@ import ( func main() { master := gobot.NewGobot() - api.NewApi(master).Start() + api.NewAPI(master).Start() pebbleAdaptor := pebble.NewPebbleAdaptor("pebble") pebbleDriver := pebble.NewPebbleDriver(pebbleAdaptor, "pebble") diff --git a/platforms/spark/spark_core_adaptor.go b/platforms/spark/spark_core_adaptor.go index 3dcd50005..1dc563cdf 100644 --- a/platforms/spark/spark_core_adaptor.go +++ b/platforms/spark/spark_core_adaptor.go @@ -11,16 +11,16 @@ import ( type SparkCoreAdaptor struct { gobot.Adaptor - DeviceId string + DeviceID string AccessToken string } -func NewSparkCoreAdaptor(name string, deviceId string, accessToken string) *SparkCoreAdaptor { +func NewSparkCoreAdaptor(name string, deviceID string, accessToken string) *SparkCoreAdaptor { return &SparkCoreAdaptor{ Adaptor: gobot.Adaptor{ Name: name, }, - DeviceId: deviceId, + DeviceID: deviceID, AccessToken: accessToken, } } @@ -40,7 +40,7 @@ func (s *SparkCoreAdaptor) AnalogRead(pin string) float64 { "params": {pin}, "access_token": {s.AccessToken}, } - url := fmt.Sprintf("%v/analogread", s.deviceUrl()) + url := fmt.Sprintf("%v/analogread", s.deviceURL()) resp := s.postToSpark(url, params) if resp != nil { return resp["return_value"].(float64) @@ -57,7 +57,7 @@ func (s *SparkCoreAdaptor) AnalogWrite(pin string, level byte) { "params": {fmt.Sprintf("%v,%v", pin, level)}, "access_token": {s.AccessToken}, } - url := fmt.Sprintf("%v/analogwrite", s.deviceUrl()) + url := fmt.Sprintf("%v/analogwrite", s.deviceURL()) s.postToSpark(url, params) } @@ -66,7 +66,7 @@ func (s *SparkCoreAdaptor) DigitalWrite(pin string, level byte) { "params": {fmt.Sprintf("%v,%v", pin, s.pinLevel(level))}, "access_token": {s.AccessToken}, } - url := fmt.Sprintf("%v/digitalwrite", s.deviceUrl()) + url := fmt.Sprintf("%v/digitalwrite", s.deviceURL()) s.postToSpark(url, params) } @@ -75,7 +75,7 @@ func (s *SparkCoreAdaptor) DigitalRead(pin string) int { "params": {pin}, "access_token": {s.AccessToken}, } - url := fmt.Sprintf("%v/digitalread", s.deviceUrl()) + url := fmt.Sprintf("%v/digitalread", s.deviceURL()) resp := s.postToSpark(url, params) if resp != nil { return int(resp["return_value"].(float64)) @@ -83,16 +83,15 @@ func (s *SparkCoreAdaptor) DigitalRead(pin string) int { return -1 } -func (s *SparkCoreAdaptor) deviceUrl() string { - return fmt.Sprintf("https://api.spark.io/v1/devices/%v", s.DeviceId) +func (s *SparkCoreAdaptor) deviceURL() string { + return fmt.Sprintf("https://api.spark.io/v1/devices/%v", s.DeviceID) } func (s *SparkCoreAdaptor) pinLevel(level byte) string { if level == 1 { return "HIGH" - } else { - return "LOW" } + return "LOW" } func (s *SparkCoreAdaptor) postToSpark(url string, params url.Values) map[string]interface{} { diff --git a/platforms/sphero/sphero_driver.go b/platforms/sphero/sphero_driver.go index 843cac480..c617725c6 100644 --- a/platforms/sphero/sphero_driver.go +++ b/platforms/sphero/sphero_driver.go @@ -14,12 +14,12 @@ type packet struct { type SpheroDriver struct { gobot.Driver - Adaptor *SpheroAdaptor - seq uint8 - async_response [][]uint8 - sync_response [][]uint8 - packet_channel chan *packet - response_channel chan []uint8 + Adaptor *SpheroAdaptor + seq uint8 + asyncResponse [][]uint8 + syncResponse [][]uint8 + packetChannel chan *packet + responseChannel chan []uint8 } func NewSpheroDriver(a *SpheroAdaptor, name string) *SpheroDriver { @@ -37,9 +37,9 @@ func NewSpheroDriver(a *SpheroAdaptor, name string) *SpheroDriver { "SetStabilizationC", }, }, - Adaptor: a, - packet_channel: make(chan *packet, 1024), - response_channel: make(chan []uint8, 1024), + Adaptor: a, + packetChannel: make(chan *packet, 1024), + responseChannel: make(chan []uint8, 1024), } } func (s *SpheroDriver) Init() bool { @@ -49,15 +49,15 @@ func (s *SpheroDriver) Init() bool { func (s *SpheroDriver) Start() bool { go func() { for { - packet := <-s.packet_channel + packet := <-s.packetChannel s.write(packet) } }() go func() { for { - response := <-s.response_channel - s.sync_response = append(s.sync_response, response) + response := <-s.responseChannel + s.syncResponse = append(s.syncResponse, response) } }() @@ -68,9 +68,9 @@ func (s *SpheroDriver) Start() bool { body := s.readBody(header[4]) if header[1] == 0xFE { async := append(header, body...) - s.async_response = append(s.async_response, async) + s.asyncResponse = append(s.asyncResponse, async) } else { - s.response_channel <- append(header, body...) + s.responseChannel <- append(header, body...) } } } @@ -79,8 +79,8 @@ func (s *SpheroDriver) Start() bool { go func() { for { var evt []uint8 - for len(s.async_response) != 0 { - evt, s.async_response = s.async_response[len(s.async_response)-1], s.async_response[:len(s.async_response)-1] + for len(s.asyncResponse) != 0 { + evt, s.asyncResponse = s.asyncResponse[len(s.asyncResponse)-1], s.asyncResponse[:len(s.asyncResponse)-1] if evt[2] == 0x07 { s.handleCollisionDetected(evt) } @@ -105,19 +105,19 @@ func (s *SpheroDriver) Halt() bool { } func (s *SpheroDriver) SetRGB(r uint8, g uint8, b uint8) { - s.packet_channel <- s.craftPacket([]uint8{r, g, b, 0x01}, 0x20) + s.packetChannel <- s.craftPacket([]uint8{r, g, b, 0x01}, 0x20) } func (s *SpheroDriver) GetRGB() []uint8 { - return s.syncResponse(s.craftPacket([]uint8{}, 0x22)) + return s.getSyncResponse(s.craftPacket([]uint8{}, 0x22)) } func (s *SpheroDriver) SetBackLED(level uint8) { - s.packet_channel <- s.craftPacket([]uint8{level}, 0x21) + s.packetChannel <- s.craftPacket([]uint8{level}, 0x21) } func (s *SpheroDriver) SetHeading(heading uint16) { - s.packet_channel <- s.craftPacket([]uint8{uint8(heading >> 8), uint8(heading & 0xFF)}, 0x01) + s.packetChannel <- s.craftPacket([]uint8{uint8(heading >> 8), uint8(heading & 0xFF)}, 0x01) } func (s *SpheroDriver) SetStabilization(on bool) { @@ -125,11 +125,11 @@ func (s *SpheroDriver) SetStabilization(on bool) { if on == false { b = 0x00 } - s.packet_channel <- s.craftPacket([]uint8{b}, 0x02) + s.packetChannel <- s.craftPacket([]uint8{b}, 0x02) } func (s *SpheroDriver) Roll(speed uint8, heading uint16) { - s.packet_channel <- s.craftPacket([]uint8{speed, uint8(heading >> 8), uint8(heading & 0xFF), 0x01}, 0x30) + s.packetChannel <- s.craftPacket([]uint8{speed, uint8(heading >> 8), uint8(heading & 0xFF), 0x01}, 0x30) } func (s *SpheroDriver) Stop() { @@ -138,27 +138,27 @@ func (s *SpheroDriver) Stop() { func (s *SpheroDriver) configureCollisionDetection() { s.Events["Collision"] = make(chan interface{}) - s.packet_channel <- s.craftPacket([]uint8{0x01, 0x40, 0x40, 0x50, 0x50, 0x60}, 0x12) + s.packetChannel <- s.craftPacket([]uint8{0x01, 0x40, 0x40, 0x50, 0x50, 0x60}, 0x12) } func (s *SpheroDriver) handleCollisionDetected(data []uint8) { gobot.Publish(s.Events["Collision"], data) } -func (s *SpheroDriver) syncResponse(packet *packet) []byte { - s.packet_channel <- packet +func (s *SpheroDriver) getSyncResponse(packet *packet) []byte { + s.packetChannel <- packet for i := 0; i < 500; i++ { - for key := range s.sync_response { - if s.sync_response[key][3] == packet.header[4] && len(s.sync_response[key]) > 6 { + for key := range s.syncResponse { + if s.syncResponse[key][3] == packet.header[4] && len(s.syncResponse[key]) > 6 { var response []byte - response, s.sync_response = s.sync_response[len(s.sync_response)-1], s.sync_response[:len(s.sync_response)-1] + response, s.syncResponse = s.syncResponse[len(s.syncResponse)-1], s.syncResponse[:len(s.syncResponse)-1] return response } } time.Sleep(10 * time.Microsecond) } - return make([]byte, 0) + return []byte{} } func (s *SpheroDriver) craftPacket(body []uint8, cid byte) *packet { @@ -183,7 +183,7 @@ func (s *SpheroDriver) write(packet *packet) { } else if length != len(buf) { fmt.Println("Not enough bytes written", s.Name) } - s.seq += 1 + s.seq++ } func (s *SpheroDriver) calculateChecksum(packet *packet) uint8 { @@ -200,18 +200,16 @@ func (s *SpheroDriver) readHeader() []uint8 { data := s.readNextChunk(5) if data == nil { return nil - } else { - return data } + return data } func (s *SpheroDriver) readBody(length uint8) []uint8 { data := s.readNextChunk(length) if data == nil { return nil - } else { - return data } + return data } func (s *SpheroDriver) readNextChunk(length uint8) []uint8 { @@ -220,7 +218,6 @@ func (s *SpheroDriver) readNextChunk(length uint8) []uint8 { l, err := s.Adaptor.sp.Read(read[:]) if err != nil || length != uint8(l) { return nil - } else { - return read } + return read } diff --git a/platforms/sphero/test_helper.go b/platforms/sphero/test_helper.go index 4c35d8d6a..5d0b5e73c 100644 --- a/platforms/sphero/test_helper.go +++ b/platforms/sphero/test_helper.go @@ -2,12 +2,12 @@ package sphero type sp struct{} -func (me sp) Write(b []byte) (int, error) { +func (s sp) Write(b []byte) (int, error) { return len(b), nil } -func (me sp) Read(b []byte) (int, error) { +func (s sp) Read(b []byte) (int, error) { return len(b), nil } -func (me sp) Close() error { +func (s sp) Close() error { return nil } diff --git a/robot.go b/robot.go index 9e6980724..10376e32d 100644 --- a/robot.go +++ b/robot.go @@ -7,11 +7,11 @@ import ( "time" ) -type JsonRobot struct { +type JSONRobot struct { Name string `json:"name"` Commands []string `json:"commands"` - Connections []*JsonConnection `json:"connections"` - Devices []*JsonDevice `json:"devices"` + Connections []*JSONConnection `json:"connections"` + Devices []*JSONDevice `json:"devices"` } type Robot struct { @@ -74,7 +74,7 @@ func (r *Robot) initName() { func (r *Robot) initCommands() { r.RobotCommands = make([]string, 0) - for k, _ := range r.Commands { + for k := range r.Commands { r.RobotCommands = append(r.RobotCommands, k) } } @@ -129,13 +129,15 @@ func (r *Robot) Connection(name string) *connection { return nil } -func (r *Robot) ToJson() *JsonRobot { - jsonRobot := new(JsonRobot) - jsonRobot.Name = r.Name - jsonRobot.Commands = r.RobotCommands - jsonRobot.Connections = make([]*JsonConnection, 0) +func (r *Robot) ToJSON() *JSONRobot { + jsonRobot := &JSONRobot{ + Name: r.Name, + Commands: r.RobotCommands, + Connections: []*JSONConnection{}, + Devices: []*JSONDevice{}, + } for _, device := range r.Devices() { - jsonDevice := device.ToJson() + jsonDevice := device.ToJSON() jsonRobot.Connections = append(jsonRobot.Connections, jsonDevice.Connection) jsonRobot.Devices = append(jsonRobot.Devices, jsonDevice) } diff --git a/test_helper.go b/test_helper.go index 53706e5c7..4fe1392f6 100644 --- a/test_helper.go +++ b/test_helper.go @@ -9,7 +9,7 @@ type testStruct struct { f float64 } -func (me *testStruct) Hello(name string, message string) string { +func (t *testStruct) Hello(name string, message string) string { return fmt.Sprintf("Hello %v! %v", name, message) } @@ -24,10 +24,10 @@ type testDriver struct { Adaptor *testAdaptor } -func (me *testDriver) Init() bool { return true } -func (me *testDriver) Start() bool { return true } -func (me *testDriver) Halt() bool { return true } -func (me *testDriver) TestDriverCommand(params map[string]interface{}) string { +func (t *testDriver) Init() bool { return true } +func (t *testDriver) Start() bool { return true } +func (t *testDriver) Halt() bool { return true } +func (t *testDriver) TestDriverCommand(params map[string]interface{}) string { name := params["name"].(string) return fmt.Sprintf("hello %v", name) } @@ -36,28 +36,32 @@ type testAdaptor struct { Adaptor } -func (me *testAdaptor) Finalize() bool { return true } -func (me *testAdaptor) Connect() bool { return true } +func (t *testAdaptor) Finalize() bool { return true } +func (t *testAdaptor) Connect() bool { return true } func newTestDriver(name string, adaptor *testAdaptor) *testDriver { - d := new(testDriver) - d.Name = name - d.Adaptor = adaptor - d.Commands = []string{ - "TestDriverCommand", - "DriverCommand", + return &testDriver{ + Driver: Driver{ + Commands: []string{ + "TestDriverCommand", + "DriverCommand", + }, + Name: name, + }, + Adaptor: adaptor, } - return d } func newTestAdaptor(name string) *testAdaptor { - a := new(testAdaptor) - a.Name = name - a.Params = map[string]interface{}{ - "param1": "1", - "param2": 2, + return &testAdaptor{ + Adaptor: Adaptor{ + Name: name, + Params: map[string]interface{}{ + "param1": "1", + "param2": 2, + }, + }, } - return a } func robotTestFunction(params map[string]interface{}) string {