소스 검색

pipoint: add extra states and auto change based on remote input.

Michael Hope 9 달 전
부모
커밋
6573330ea8
9개의 변경된 파일149개의 추가작업 그리고 25개의 파일을 삭제
  1. 1 1
      Makefile
  2. 4 0
      cycle.go
  3. 33 0
      hold.go
  4. 8 1
      locate.go
  5. 58 0
      orientate.go
  6. 0 0
      overview.svg
  7. 5 0
      param.go
  8. 17 14
      pipoint.go
  9. 23 9
      run.go

+ 1 - 1
Makefile 파일 보기

@@ -22,7 +22,7 @@ LDFLAGS = -ldflags "-X $(PKG).Version=$(VERSION)"
22 22
 
23 23
 # Watch for changes, build, and push.
24 24
 watch:
25
-	watchman-make -p '**.go' -t push
25
+	watchman-make -p '**/*.go' -t push
26 26
 
27 27
 run:
28 28
 	go get $(LDFLAGS) $(PKG)/pipoint

+ 4 - 0
cycle.go 파일 보기

@@ -25,6 +25,10 @@ type CycleState struct {
25 25
 	cycle float64
26 26
 }
27 27
 
28
+func (s *CycleState) Name() string {
29
+	return "Cycle"
30
+}
31
+
28 32
 // Update reacts to changes in parameters.
29 33
 func (s *CycleState) Update(param *Param) {
30 34
 	switch param {

+ 33 - 0
hold.go 파일 보기

@@ -0,0 +1,33 @@
1
+// Copyright 2017 Google Inc.
2
+//
3
+// Licensed under the Apache License, Version 2.0 (the "License");
4
+// you may not use this file except in compliance with the License.
5
+// You may obtain a copy of the License at
6
+//
7
+//     http://www.apache.org/licenses/LICENSE-2.0
8
+//
9
+// Unless required by applicable law or agreed to in writing, software
10
+// distributed under the License is distributed on an "AS IS" BASIS,
11
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
+// See the License for the specific language governing permissions and
13
+// limitations under the License.
14
+//
15
+
16
+package pipoint
17
+
18
+// HoldState executes when the camera is tracking the rover.
19
+type HoldState struct {
20
+	pi *PiPoint
21
+}
22
+
23
+func (s *HoldState) Name() string {
24
+	return "Hold"
25
+}
26
+
27
+// Update is called when a param is updated.
28
+func (s *HoldState) Update(param *Param) {
29
+	switch param {
30
+	case s.pi.mark:
31
+		s.pi.state.Dec()
32
+	}
33
+}

+ 8 - 1
locate.go 파일 보기

@@ -17,7 +17,12 @@ package pipoint
17 17
 
18 18
 // LocateState runs initially to locate the base unit.
19 19
 type LocateState struct {
20
-	pi *PiPoint
20
+	name string
21
+	pi   *PiPoint
22
+}
23
+
24
+func (s *LocateState) Name() string {
25
+	return "Locate"
21 26
 }
22 27
 
23 28
 // Update is called when a param is updated.
@@ -31,5 +36,7 @@ func (s *LocateState) Update(param *Param) {
31 36
 		s.pi.offset.Set(&Attitude{
32 37
 			Yaw: s.pi.attitude.Get().(*Attitude).Yaw,
33 38
 		})
39
+	case s.pi.mark:
40
+		s.pi.state.Inc()
34 41
 	}
35 42
 }

+ 58 - 0
orientate.go 파일 보기

@@ -0,0 +1,58 @@
1
+// Copyright 2017 Google Inc.
2
+//
3
+// Licensed under the Apache License, Version 2.0 (the "License");
4
+// you may not use this file except in compliance with the License.
5
+// You may obtain a copy of the License at
6
+//
7
+//     http://www.apache.org/licenses/LICENSE-2.0
8
+//
9
+// Unless required by applicable law or agreed to in writing, software
10
+// distributed under the License is distributed on an "AS IS" BASIS,
11
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
+// See the License for the specific language governing permissions and
13
+// limitations under the License.
14
+//
15
+
16
+package pipoint
17
+
18
+// OrientateState runs to set the pan orientation.
19
+type OrientateState struct {
20
+	name string
21
+	pi *PiPoint
22
+}
23
+
24
+func (s *OrientateState) Name() string {
25
+	return "Orientate"
26
+}
27
+
28
+// Update is called when a param is updated.
29
+func (s *OrientateState) Update(param *Param) {
30
+	switch param {
31
+	case s.pi.neu:
32
+		s.pi.rover.Set(param.Get())
33
+	case s.pi.mark:
34
+		s.pi.state.Inc()
35
+	}
36
+
37
+	if param != s.pi.rover {
38
+		return
39
+	}
40
+	
41
+	if !s.pi.rover.Ok() || !s.pi.base.Ok() {
42
+		return
43
+	}
44
+
45
+	rover := s.pi.rover.Get().(*NEUPosition)
46
+	base := s.pi.base.Get().(*NEUPosition)
47
+	offset := s.pi.baseOffset.Get().(*NEUPosition)
48
+
49
+	att, err := point(rover, base, offset)
50
+
51
+	if err != nil {
52
+		return
53
+	}
54
+
55
+	s.pi.offset.Set(&Attitude{
56
+		Yaw: -att.Yaw,
57
+	})
58
+}

+ 0 - 0
overview.svg 파일 보기


+ 5 - 0
param.go 파일 보기

@@ -121,6 +121,11 @@ func (p *Param) Inc() error {
121 121
 	return p.SetInt(p.GetInt() + 1)
122 122
 }
123 123
 
124
+// Dec tries to decrement the integer value.
125
+func (p *Param) Dec() error {
126
+	return p.SetInt(p.GetInt() - 1)
127
+}
128
+
124 129
 // Finalise marks the param as always valid.
125 130
 func (p *Param) Finalise() {
126 131
 	p.final = true

+ 17 - 14
pipoint.go 파일 보기

@@ -16,7 +16,6 @@
16 16
 package pipoint
17 17
 
18 18
 import (
19
-	"fmt"
20 19
 	"log"
21 20
 	"time"
22 21
 
@@ -36,6 +35,7 @@ var (
36 35
 
37 36
 // State is a handler for the current state of the system.
38 37
 type State interface {
38
+	Name() string
39 39
 	Update(param *Param)
40 40
 }
41 41
 
@@ -103,7 +103,9 @@ func NewPiPoint() *PiPoint {
103 103
 
104 104
 	p.states = []State{
105 105
 		&LocateState{pi: p},
106
+		&OrientateState{pi: p},
106 107
 		&RunState{pi: p},
108
+		&HoldState{pi: p},
107 109
 		&CycleState{pi: p},
108 110
 	}
109 111
 
@@ -198,18 +200,28 @@ func (pi *PiPoint) predict(gps *Position) {
198 200
 }
199 201
 
200 202
 func (pi *PiPoint) update(param *Param) {
201
-	state := pi.state.GetInt()
202
-
203
-	if state >= 0 && state < len(pi.states) {
204
-		pi.states[state].Update(param)
203
+	if state := pi.getState(); state != nil {
204
+		state.Update(param)
205 205
 	}
206 206
 
207 207
 	pi.announce(param)
208 208
 	pi.log.Printf("%s %T %#v\n", param.Name, param.Get(), param.Get())
209 209
 }
210 210
 
211
+func (pi *PiPoint) getState() State {
212
+	state := pi.state.GetInt()
213
+	if state >= 0 && state < len(pi.states) {
214
+		return pi.states[state]
215
+	}
216
+	return nil
217
+}
218
+
211 219
 func (pi *PiPoint) announce(param *Param) {
212 220
 	switch param {
221
+	case pi.state:
222
+		if state := pi.getState(); state != nil {
223
+			pi.audio.Say(state.Name())
224
+		}
213 225
 	case pi.link:
214 226
 		link := param.GetInt()
215 227
 		if link != pi.linkLast {
@@ -225,15 +237,6 @@ func (pi *PiPoint) announce(param *Param) {
225 237
 		if param.GetInt() >= 3 {
226 238
 			pi.audio.Say("GPS ready")
227 239
 		}
228
-	case pi.mark:
229
-		pi.audio.Say("Mark")
230
-	case pi.seconds:
231
-		if (param.GetInt()%5) == 0 && pi.vel.Ok() {
232
-			kph := pi.vel.GetFloat64() * 3.6
233
-			if kph >= 1 {
234
-				pi.audio.Say(fmt.Sprintf("%.0f kph", kph))
235
-			}
236
-		}
237 240
 	}
238 241
 }
239 242
 

+ 23 - 9
run.go 파일 보기

@@ -26,34 +26,48 @@ type RunState struct {
26 26
 	pi *PiPoint
27 27
 }
28 28
 
29
+func (s *RunState) Name() string {
30
+	return "Run"
31
+}
32
+
29 33
 // Update is called when a param is updated.
30 34
 func (s *RunState) Update(param *Param) {
31 35
 	switch param {
32 36
 	case s.pi.neu:
33 37
 		s.pi.rover.Set(param.Get())
38
+	case s.pi.seconds:
39
+		if (param.GetInt()%5) == 0 && s.pi.vel.Ok() {
40
+			kph := s.pi.vel.GetFloat64() * 3.6
41
+			if kph >= 2 {
42
+				s.pi.audio.Say(fmt.Sprintf("%.0f kph", kph))
43
+			}
44
+		}
45
+	case s.pi.mark:
46
+		s.pi.state.Inc()
47
+	}
48
+
49
+	if param != s.pi.rover {
50
+		return
34 51
 	}
35 52
 
36 53
 	if !s.pi.rover.Ok() || !s.pi.base.Ok() {
37
-		// Location is invalid or old.
38
-		log.Println("run: skipping as invalid or old", s.pi.rover.Ok(), s.pi.base.Ok())
39 54
 		return
40 55
 	}
41 56
 
57
+	
42 58
 	rover := s.pi.rover.Get().(*NEUPosition)
43 59
 	base := s.pi.base.Get().(*NEUPosition)
44
-	offset := s.pi.baseOffset.Get().(*NEUPosition)
60
+	baseOffset := s.pi.baseOffset.Get().(*NEUPosition)
45 61
 
46
-	att, err := point(rover, base, offset)
62
+	att, err := point(rover, base, baseOffset)
47 63
 	if err != nil {
48 64
 		log.Printf("point: %v\n", err)
49 65
 		return
50 66
 	}
51 67
 
52
-	if param == s.pi.neu {
53
-		offset := s.pi.offset.Get().(*Attitude)
54
-		s.pi.pan.Set(WrapAngle(att.Yaw + offset.Yaw))
55
-		s.pi.tilt.Set(WrapAngle(att.Pitch + offset.Pitch))
56
-	}
68
+	offset := s.pi.offset.Get().(*Attitude)
69
+	s.pi.pan.Set(WrapAngle(att.Yaw + offset.Yaw))
70
+	s.pi.tilt.Set(WrapAngle(att.Pitch + offset.Pitch))
57 71
 }
58 72
 
59 73
 func point(rover, base, offset *NEUPosition) (*Attitude, error) {