1
0
mirror of https://github.com/hybridgroup/gobot.git synced 2025-05-11 19:29:20 +08:00

Merge pull request #161 from hybridgroup/variables-and-functions

Variables and functions for spark adaptor
This commit is contained in:
Adrian Zankich 2014-12-28 14:10:14 +01:00
commit 1b571123e1
4 changed files with 210 additions and 19 deletions

View File

@ -0,0 +1,31 @@
package main
import (
"fmt"
"github.com/hybridgroup/gobot"
"github.com/hybridgroup/gobot/platforms/spark"
)
func main() {
gbot := gobot.NewGobot()
sparkCore := spark.NewSparkCoreAdaptor("spark", "DEVICE_ID", "ACCESS_TOKEN")
work := func() {
if result, err := sparkCore.Function("brew", "202,230"); err != nil {
fmt.Println(err)
} else {
fmt.Println("result from \"brew\":", result)
}
}
robot := gobot.NewRobot("spark",
[]gobot.Connection{sparkCore},
work,
)
gbot.AddRobot(robot)
gbot.Start()
}

View File

@ -0,0 +1,34 @@
package main
import (
"fmt"
"time"
"github.com/hybridgroup/gobot"
"github.com/hybridgroup/gobot/platforms/spark"
)
func main() {
gbot := gobot.NewGobot()
sparkCore := spark.NewSparkCoreAdaptor("spark", "DEVICE_ID", "ACCESS_TOKEN")
work := func() {
gobot.Every(1*time.Second, func() {
if temp, err := sparkCore.Variable("temperature"); err != nil {
fmt.Println(err)
} else {
fmt.Println("result from \"temperature\" is:", temp)
}
})
}
robot := gobot.NewRobot("spark",
[]gobot.Connection{sparkCore},
work,
)
gbot.AddRobot(robot)
gbot.Start()
}

View File

@ -7,6 +7,7 @@ import (
"io/ioutil"
"net/http"
"net/url"
"strconv"
"github.com/hybridgroup/gobot"
"github.com/hybridgroup/gobot/platforms/gpio"
@ -57,7 +58,7 @@ func (s *SparkCoreAdaptor) AnalogRead(pin string) (val int, err error) {
url := fmt.Sprintf("%v/analogread", s.deviceURL())
resp, err := s.postToSpark(url, params)
resp, err := s.requestToSpark("POST", url, params)
if err == nil {
val = int(resp["return_value"].(float64))
return
@ -78,7 +79,7 @@ func (s *SparkCoreAdaptor) AnalogWrite(pin string, level byte) (err error) {
"access_token": {s.AccessToken},
}
url := fmt.Sprintf("%v/analogwrite", s.deviceURL())
_, err = s.postToSpark(url, params)
_, err = s.requestToSpark("POST", url, params)
return
}
@ -89,7 +90,7 @@ func (s *SparkCoreAdaptor) DigitalWrite(pin string, level byte) (err error) {
"access_token": {s.AccessToken},
}
url := fmt.Sprintf("%v/digitalwrite", s.deviceURL())
_, err = s.postToSpark(url, params)
_, err = s.requestToSpark("POST", url, params)
return err
}
@ -100,7 +101,7 @@ func (s *SparkCoreAdaptor) DigitalRead(pin string) (val int, err error) {
"access_token": {s.AccessToken},
}
url := fmt.Sprintf("%v/digitalread", s.deviceURL())
resp, err := s.postToSpark(url, params)
resp, err := s.requestToSpark("POST", url, params)
if err == nil {
val = int(resp["return_value"].(float64))
return
@ -108,6 +109,49 @@ func (s *SparkCoreAdaptor) DigitalRead(pin string) (val int, err error) {
return -1, err
}
// Variable returns a core variable value as a string
func (s *SparkCoreAdaptor) Variable(name string) (result string, err error) {
url := fmt.Sprintf("%v/%s?access_token=%s", s.deviceURL(), name, s.AccessToken)
resp, err := s.requestToSpark("GET", url, nil)
if err != nil {
return
}
val := resp["result"]
switch val.(type) {
case bool:
result = strconv.FormatBool(val.(bool))
case float64:
result = strconv.FormatFloat(val.(float64), 'f', -1, 64)
case string:
result = val.(string)
}
return
}
// Function executes a core function and
// returns value from request.
// Takes a String as the only argument and returns an Int.
// If function is not defined in core, it will time out
func (s *SparkCoreAdaptor) Function(name string, args string) (val int, err error) {
params := url.Values{
"args": {args},
"access_token": {s.AccessToken},
}
url := fmt.Sprintf("%s/%s", s.deviceURL(), name)
resp, err := s.requestToSpark("POST", url, params)
if err != nil {
return -1, err
}
val = int(resp["return_value"].(float64))
return
}
// setAPIServer sets spark cloud api server, this can be used to change from default api.spark.io
func (s *SparkCoreAdaptor) setAPIServer(server string) {
s.APIServer = server
@ -129,10 +173,17 @@ func (s *SparkCoreAdaptor) pinLevel(level byte) string {
return "LOW"
}
// postToSpark makes POST request to spark cloud server, return err != nil if there is
// requestToSpark makes request to spark cloud server, return err != nil if there is
// any issue with the request.
func (s *SparkCoreAdaptor) postToSpark(url string, params url.Values) (m map[string]interface{}, err error) {
resp, err := http.PostForm(url, params)
func (s *SparkCoreAdaptor) requestToSpark(method string, url string, params url.Values) (m map[string]interface{}, err error) {
var resp *http.Response
if method == "POST" {
resp, err = http.PostForm(url, params)
} else if method == "GET" {
resp, err = http.Get(url)
}
if err != nil {
return
}
@ -146,12 +197,9 @@ func (s *SparkCoreAdaptor) postToSpark(url string, params url.Values) (m map[str
json.Unmarshal(buf, &m)
if resp.Status != "200 OK" {
if _, ok := m["error"]; ok {
err = errors.New(m["error"].(string))
} else {
err = errors.New(fmt.Sprintf("&v: error communicating to the spark cloud", resp.Status))
}
return
err = errors.New(fmt.Sprintf("&v: error communicating to the spark cloud", resp.Status))
} else if _, ok := m["error"]; ok {
err = errors.New(m["error"].(string))
}
return

View File

@ -72,6 +72,7 @@ func TestNewSparkCoreAdaptor(t *testing.T) {
}
gobot.Assert(t, spark.APIServer, "https://api.spark.io")
gobot.Assert(t, spark.Name(), "bot")
}
func TestSparkCoreAdaptorConnect(t *testing.T) {
@ -110,7 +111,6 @@ func TestSparkCoreAdaptorAnalogRead(t *testing.T) {
val, _ = a.AnalogRead("A1")
gobot.Assert(t, val, 0)
}
func TestSparkCoreAdaptorPwmWrite(t *testing.T) {
@ -195,8 +195,86 @@ func TestSparkCoreAdaptorDigitalRead(t *testing.T) {
gobot.Assert(t, val, -1)
}
func TestSparkCoreAdaptorSetAPIServer(t *testing.T) {
func TestSparkCoreAdaptorFunction(t *testing.T) {
response := `{"return_value": 1}`
a := initTestSparkCoreAdaptor()
testServer := getDummyResponseForPath("/"+a.DeviceID+"/hello", response, t)
a.setAPIServer(testServer.URL)
val, _ := a.Function("hello", "100,200")
gobot.Assert(t, val, 1)
testServer.Close()
// When not existent
response = `{"ok": false, "error": "timeout"}`
testServer = getDummyResponseForPath("/"+a.DeviceID+"/hello", response, t)
a.setAPIServer(testServer.URL)
_, err := a.Function("hello", "")
gobot.Assert(t, err.Error(), "timeout")
testServer.Close()
}
func TestSparkCoreAdaptorVariable(t *testing.T) {
// When String
response := `{"result": "1"}`
a := initTestSparkCoreAdaptor()
testServer := getDummyResponseForPath("/"+a.DeviceID+"/variable_name", response, t)
a.setAPIServer(testServer.URL)
val, _ := a.Variable("variable_name")
gobot.Assert(t, val, "1")
testServer.Close()
// When float
response = `{"result": 1.1}`
testServer = getDummyResponseForPath("/"+a.DeviceID+"/variable_name", response, t)
a.setAPIServer(testServer.URL)
val, _ = a.Variable("variable_name")
gobot.Assert(t, val, "1.1")
testServer.Close()
// When int
response = `{"result": 1}`
testServer = getDummyResponseForPath("/"+a.DeviceID+"/variable_name", response, t)
a.setAPIServer(testServer.URL)
val, _ = a.Variable("variable_name")
gobot.Assert(t, val, "1")
testServer.Close()
// When bool
response = `{"result": true}`
testServer = getDummyResponseForPath("/"+a.DeviceID+"/variable_name", response, t)
a.setAPIServer(testServer.URL)
val, _ = a.Variable("variable_name")
gobot.Assert(t, val, "true")
testServer.Close()
// When not existent
response = `{"ok": false, "error": "Variable not found"}`
testServer = getDummyResponseForPath("/"+a.DeviceID+"/not_existent", response, t)
a.setAPIServer(testServer.URL)
_, err := a.Variable("not_existent")
gobot.Assert(t, err.Error(), "Variable not found")
testServer.Close()
}
func TestSparkCoreAdaptorSetAPIServer(t *testing.T) {
a := initTestSparkCoreAdaptor()
apiServer := "new_api_server"
gobot.Refute(t, a.APIServer, apiServer)
@ -234,9 +312,9 @@ func TestSparkCoreAdaptorPostToSpark(t *testing.T) {
// When error on request
vals := url.Values{}
vals.Add("error", "error")
resp, err := a.postToSpark("http://invalid%20host.com", vals)
resp, err := a.requestToSpark("POST", "http://invalid%20host.com", vals)
if err == nil {
t.Errorf("postToSpark() should return an error when request was unsuccessful but returned", resp)
t.Errorf("requestToSpark() should return an error when request was unsuccessful but returned", resp)
}
// When error reading body
@ -248,9 +326,9 @@ func TestSparkCoreAdaptorPostToSpark(t *testing.T) {
})
defer testServer.Close()
resp, err = a.postToSpark(testServer.URL+"/existent", vals)
resp, err = a.requestToSpark("POST", testServer.URL+"/existent", vals)
if err == nil {
t.Errorf("postToSpark() should return an error when status is not 200 but returned", resp)
t.Errorf("requestToSpark() should return an error when status is not 200 but returned", resp)
}
}