Merge pull request #322 from radovskyb/dev
fixed undefined method errors
This commit is contained in:
commit
8f4320a439
|
@ -24,7 +24,7 @@ Example:
|
|||
|
||||
work := func() {
|
||||
drone.TakeOff()
|
||||
gobot.On(drone.Event("flying"), func(data interface{}) {
|
||||
drone.On(drone.Event("flying"), func(data interface{}) {
|
||||
gobot.After(3*time.Second, func() {
|
||||
drone.Land()
|
||||
})
|
||||
|
|
|
@ -28,28 +28,28 @@ Example:
|
|||
)
|
||||
|
||||
work := func() {
|
||||
gobot.On(joystick.Event("square_press"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("square_press"), func(data interface{}) {
|
||||
fmt.Println("square_press")
|
||||
})
|
||||
gobot.On(joystick.Event("square_release"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("square_release"), func(data interface{}) {
|
||||
fmt.Println("square_release")
|
||||
})
|
||||
gobot.On(joystick.Event("triangle_press"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("triangle_press"), func(data interface{}) {
|
||||
fmt.Println("triangle_press")
|
||||
})
|
||||
gobot.On(joystick.Event("triangle_release"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("triangle_release"), func(data interface{}) {
|
||||
fmt.Println("triangle_release")
|
||||
})
|
||||
gobot.On(joystick.Event("left_x"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("left_x"), func(data interface{}) {
|
||||
fmt.Println("left_x", data)
|
||||
})
|
||||
gobot.On(joystick.Event("left_y"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("left_y"), func(data interface{}) {
|
||||
fmt.Println("left_y", data)
|
||||
})
|
||||
gobot.On(joystick.Event("right_x"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("right_x"), func(data interface{}) {
|
||||
fmt.Println("right_x", data)
|
||||
})
|
||||
gobot.On(joystick.Event("right_y"), func(data interface{}) {
|
||||
joystick.On(joystick.Event("right_y"), func(data interface{}) {
|
||||
fmt.Println("right_y", data)
|
||||
})
|
||||
}
|
||||
|
|
|
@ -26,7 +26,7 @@ Example:
|
|||
l := leap.NewDriver(leapMotionAdaptor)
|
||||
|
||||
work := func() {
|
||||
gobot.On(l.Event("message"), func(data interface{}) {
|
||||
l.On(l.Event("message"), func(data interface{}) {
|
||||
fmt.Println(data.(leap.Frame))
|
||||
})
|
||||
}
|
||||
|
|
|
@ -24,7 +24,7 @@ Example:
|
|||
iris := mavlink.NewDriver(adaptor)
|
||||
|
||||
work := func() {
|
||||
gobot.Once(iris.Event("packet"), func(data interface{}) {
|
||||
iris.Once(iris.Event("packet"), func(data interface{}) {
|
||||
packet := data.(*common.MAVLinkPacket)
|
||||
|
||||
dataStream := common.NewRequestDataStream(100,
|
||||
|
@ -39,7 +39,7 @@ Example:
|
|||
))
|
||||
})
|
||||
|
||||
gobot.On(iris.Event("message"), func(data interface{}) {
|
||||
iris.On(iris.Event("message"), func(data interface{}) {
|
||||
if data.(common.MAVLinkMessage).Id() == 30 {
|
||||
message := data.(*common.Attitude)
|
||||
fmt.Println("Attitude")
|
||||
|
|
|
@ -23,25 +23,25 @@ Example:
|
|||
neuro := neurosky.NewDriver(adaptor)
|
||||
|
||||
work := func() {
|
||||
gobot.On(neuro.Event("extended"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("extended"), func(data interface{}) {
|
||||
fmt.Println("Extended", data)
|
||||
})
|
||||
gobot.On(neuro.Event("signal"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("signal"), func(data interface{}) {
|
||||
fmt.Println("Signal", data)
|
||||
})
|
||||
gobot.On(neuro.Event("attention"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("attention"), func(data interface{}) {
|
||||
fmt.Println("Attention", data)
|
||||
})
|
||||
gobot.On(neuro.Event("meditation"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("meditation"), func(data interface{}) {
|
||||
fmt.Println("Meditation", data)
|
||||
})
|
||||
gobot.On(neuro.Event("blink"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("blink"), func(data interface{}) {
|
||||
fmt.Println("Blink", data)
|
||||
})
|
||||
gobot.On(neuro.Event("wave"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("wave"), func(data interface{}) {
|
||||
fmt.Println("Wave", data)
|
||||
})
|
||||
gobot.On(neuro.Event("eeg"), func(data interface{}) {
|
||||
neuro.On(neuro.Event("eeg"), func(data interface{}) {
|
||||
eeg := data.(neurosky.EEG)
|
||||
fmt.Println("Delta", eeg.Delta)
|
||||
fmt.Println("Theta", eeg.Theta)
|
||||
|
|
Loading…
Reference in New Issue