-
Notifications
You must be signed in to change notification settings - Fork 74
/
board.proto
263 lines (212 loc) · 6.82 KB
/
board.proto
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
syntax = "proto3";
package viam.component.board.v1;
import "common/v1/common.proto";
import "google/api/annotations.proto";
import "google/protobuf/duration.proto";
import "google/protobuf/struct.proto";
option go_package = "go.viam.com/api/component/board/v1";
option java_package = "com.viam.component.board.v1";
// BoardService services all Boards associated with a robot
service BoardService {
rpc SetGPIO(SetGPIORequest) returns (SetGPIOResponse) {
option (google.api.http) = {
put: "/viam/api/v1/component/board/{name}/gpio"
};
}
// GetGPIO gets the high/low state of the given pin of a board of the underlying robot.
rpc GetGPIO(GetGPIORequest) returns (GetGPIOResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{name}/gpio"
};
}
// PWM gets the duty cycle of the given pin of a board of the underlying robot.
rpc PWM(PWMRequest) returns (PWMResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{name}/pwm"
};
}
// SetPWM sets the given pin of a board of the underlying robot to the given duty cycle.
rpc SetPWM(SetPWMRequest) returns (SetPWMResponse) {
option (google.api.http) = {
put: "/viam/api/v1/component/board/{name}/pwm"
};
}
// PWMFrequency gets the PWM frequency of the given pin of a board of the underlying robot.
rpc PWMFrequency(PWMFrequencyRequest) returns (PWMFrequencyResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{name}/pwm_freq"
};
}
// SetPWMFrequency sets the given pin of a board of the underlying robot to the given PWM frequency. 0 will use the board's default PWM frequency.
rpc SetPWMFrequency(SetPWMFrequencyRequest) returns (SetPWMFrequencyResponse) {
option (google.api.http) = {
put: "/viam/api/v1/component/board/{name}/pwm_freq"
};
}
// DoCommand sends/receives arbitrary commands
rpc DoCommand(common.v1.DoCommandRequest) returns (common.v1.DoCommandResponse) {
option (google.api.http) = {
post: "/viam/api/v1/component/board/{name}/do_command"
};
}
// Analog Reader
// ReadAnalogReader reads off the current value of an analog reader of a board of the underlying robot.
rpc ReadAnalogReader(ReadAnalogReaderRequest) returns (ReadAnalogReaderResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{board_name}/analog_reader/{analog_reader_name}/read"
};
}
//Analog Writer
// WriteAnalog writes the value to the analog writer of the board.
rpc WriteAnalog(WriteAnalogRequest) returns (WriteAnalogResponse) {
option (google.api.http) = {
put: "/viam/api/v1/component/board/{name}/analog_write"
};
}
// Digital Interrupt
// GetDigitalInterruptValue returns the current value of the interrupt which is based on the type of interrupt.
rpc GetDigitalInterruptValue(GetDigitalInterruptValueRequest) returns (GetDigitalInterruptValueResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{board_name}/digital_interrupt/{digital_interrupt_name}/value"
};
}
// StreamTicks starts a stream of ticks for the given digital interrupts.
rpc StreamTicks(StreamTicksRequest) returns (stream StreamTicksResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{name}/tick_stream"
};
}
// Power Management
// `SetPowerMode` sets the power consumption mode of the board to the requested setting for the given duration.
rpc SetPowerMode(SetPowerModeRequest) returns (SetPowerModeResponse) {
option (google.api.http) = {
put: "/viam/api/v1/component/board/{name}/power_mode"
};
}
// GetGeometries returns the geometries of the component in their current configuration.
rpc GetGeometries(common.v1.GetGeometriesRequest) returns (common.v1.GetGeometriesResponse) {
option (google.api.http) = {
get: "/viam/api/v1/component/board/{name}/geometries"
};
}
}
message Status {
map<string, int32> analogs = 1;
map<string, int64> digital_interrupts = 2;
}
message SetGPIORequest {
string name = 1;
string pin = 2;
bool high = 3;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message SetGPIOResponse {}
message GetGPIORequest {
string name = 1;
string pin = 2;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message GetGPIOResponse {
bool high = 1;
}
message PWMRequest {
string name = 1;
string pin = 2;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message PWMResponse {
double duty_cycle_pct = 1; // 0-1
}
message SetPWMRequest {
string name = 1;
string pin = 2;
double duty_cycle_pct = 3; // 0-1
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message SetPWMResponse {}
message PWMFrequencyRequest {
string name = 1;
string pin = 2;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message PWMFrequencyResponse {
uint64 frequency_hz = 1;
}
message SetPWMFrequencyRequest {
string name = 1;
string pin = 2;
uint64 frequency_hz = 3;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message SetPWMFrequencyResponse {}
// Analog Reader
message ReadAnalogReaderRequest {
string board_name = 1;
string analog_reader_name = 2;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message ReadAnalogReaderResponse {
int32 value = 1;
float min_range = 2;
float max_range = 3;
float step_size = 4;
}
// Analog Writer
message WriteAnalogRequest {
string name = 1;
string pin = 2;
int32 value = 3;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message WriteAnalogResponse {}
// Digital Interrupt
message GetDigitalInterruptValueRequest {
string board_name = 1;
string digital_interrupt_name = 2;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message GetDigitalInterruptValueResponse {
int64 value = 1;
}
message StreamTicksRequest {
// Board name
string name = 1;
// Name of digital interrupts to recieve ticks from
repeated string pin_names = 2;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message StreamTicksResponse {
// name of interrupt
string pin_name = 1;
// Time in nanoseconds of a tick
uint64 time = 2;
// Value high or low of the tick
bool high = 3;
}
// Power Management API
enum PowerMode {
POWER_MODE_UNSPECIFIED = 0;
POWER_MODE_NORMAL = 1;
POWER_MODE_OFFLINE_DEEP = 2;
}
message SetPowerModeRequest {
// name of board
string name = 1;
// Requested power mode
PowerMode power_mode = 2;
// Requested duration to stay in `power_mode`
optional google.protobuf.Duration duration = 3;
// Additional arguments to the method
google.protobuf.Struct extra = 99;
}
message SetPowerModeResponse {}