-
Notifications
You must be signed in to change notification settings - Fork 551
/
robot_command.proto
211 lines (161 loc) · 7.08 KB
/
robot_command.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
// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved.
//
// Downloading, reproducing, distributing or otherwise using the SDK Software
// is subject to the terms and conditions of the Boston Dynamics Software
// Development Kit License (20191101-BDSDK-SL).
syntax = "proto3";
package bosdyn.api;
option java_outer_classname = "RobotCommandProto";
import "bosdyn/api/basic_command.proto";
import "bosdyn/api/full_body_command.proto";
import "bosdyn/api/header.proto";
import "bosdyn/api/lease.proto";
import "bosdyn/api/robot_state.proto";
import "bosdyn/api/synchronized_command.proto";
// A command for a robot to execute.
// The server decides if a set of commands is valid for a given robot and configuration.
message RobotCommand {
oneof command {
// Commands which require control of entire robot.
FullBodyCommand.Request full_body_command = 1;
// A synchronized command, for partial or full control of robot.
SynchronizedCommand.Request synchronized_command = 3;
}
// mobility_command was removed in 4.0, please use synchronized_command instead.
reserved 2;
}
// Command specific feedback. Distance to goal, estimated time remaining, probability of
// success, etc. Note that the feedback should directly mirror the command request.
message RobotCommandFeedback {
oneof command {
// Commands which require control of entire robot.
FullBodyCommand.Feedback full_body_feedback = 2;
// A synchronized command, for partial or full control of robot.
SynchronizedCommand.Feedback synchronized_feedback = 3;
}
// mobility_feedback was removed in 4.0, Please use RobotCommand.synchronized_command and
// synchronized_feedback instead.
reserved 1;
}
// A RobotCommand request message includes the lease and command as well as a clock
// identifier to ensure timesync when issuing commands with a fixed length.
message RobotCommandRequest {
// Common request header.
RequestHeader header = 1;
// The Lease to show ownership of the robot.
Lease lease = 2;
// A command for a robot to execute. A command can be comprised of several subcommands.
RobotCommand command = 3;
// Identifier provided by the time sync service to verify time sync between robot and client.
string clock_identifier = 4;
}
// The RobotCommand response message contains a robot command id that can be used to poll the
// robot command service for feedback on the state of the command.
message RobotCommandResponse {
// Common response header.
ResponseHeader header = 1;
// Details about how the lease was used.
LeaseUseResult lease_use_result = 2;
enum Status {
STATUS_UNKNOWN = 0; // An unknown / unexpected error occurred.
STATUS_OK = 1; // Request was accepted.
// [Programming Error]
STATUS_INVALID_REQUEST = 2; // Request was invalid / malformed in some way.
STATUS_UNSUPPORTED = 3; // The robot does not understand this command.
// [Timesync Error]
STATUS_NO_TIMESYNC = 4; // Client has not done timesync with robot.
STATUS_EXPIRED = 5; // The command was received after its end_time had already passed.
STATUS_TOO_DISTANT = 6; // The command end time was too far in the future.
// [Hardware Error]
STATUS_NOT_POWERED_ON = 7; // The robot must be powered on to accept a command.
// [Robot State Error]
STATUS_BEHAVIOR_FAULT = 9; // The robot must not have behavior faults.
STATUS_DOCKED = 10; // The robot cannot be docked for certain commands.
//// [Frame Error]
STATUS_UNKNOWN_FRAME = 8; // The frame_name for a command was not a known frame.
}
// Return status for a request.
Status status = 3;
// Human-readable error description. Not for programmatic analysis.
string message = 4;
// Unique identifier for the command, If empty, command was not accepted.
uint32 robot_command_id = 5;
}
// The RobotCommandFeedback request message, which can get the feedback for a specific
// robot command id number.
message RobotCommandFeedbackRequest {
// Common request header.
RequestHeader header = 1;
// Unique identifier for the command, provided by StartRequest.
uint32 robot_command_id = 2;
}
// The RobotCommandFeedback response message, which contains the progress of the robot command.
message RobotCommandFeedbackResponse {
// Common response header.
ResponseHeader header = 1;
// Details about how the lease was used.
LeaseUseResult lease_use_result = 5;
// Command specific feedback.
RobotCommandFeedback feedback = 4;
// status removed in 4.0. Please use RobotCommandResponse.status instead.
reserved 2;
// message removed in 4.0. Please use RobotCommandResponse.message instead.
reserved 3;
}
// A ClearBehaviorFault request message has the associated behavior fault id to be cleared.
message ClearBehaviorFaultRequest {
// Common request header.
RequestHeader header = 1;
// The Lease to show ownership of the robot.
Lease lease = 2;
// Unique identifier for the error
uint32 behavior_fault_id = 3;
}
// A ClearBehaviorFault response message has status indicating whether the service cleared
// the fault or not.
message ClearBehaviorFaultResponse {
// Common response header.
ResponseHeader header = 1;
// Details about how the lease was used.
LeaseUseResult lease_use_result = 2;
enum Status {
// An unknown / unexpected error occurred.
STATUS_UNKNOWN = 0;
// The BehaviorFault has been cleared.
STATUS_CLEARED = 1;
// The BehaviorFault could not be cleared.
STATUS_NOT_CLEARED = 2;
}
// Return status for a request.
Status status = 3;
// Echo back the behavior fault if it was active at the time of request.
BehaviorFault behavior_fault = 4;
// Blocking hardware faults for an unclearable behavior fault.
repeated SystemFault blocking_system_faults = 5;
}
message JointControlStreamRequest {
// Common request header.
RequestHeader header = 1;
// Joint command details
JointCommand.UpdateRequest joint_command = 2;
// Optional contact advice which may improve kinematic odometry.
JointCommand.ContactAdvice contact_advice = 3;
}
message JointControlStreamResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
STATUS_UNKNOWN = 0; // An unknown / unexpected error occurred.
STATUS_OK = 1; // Steam was accepted and ended normally
// [Programming Error]
STATUS_INVALID_REQUEST = 2; // Request was invalid / malformed in some way.
STATUS_INACTIVE = 3; // The robot is not in joint control mode.
// [Timesync Error]
STATUS_EXPIRED = 4; // The command was received after its end_time had already passed.
STATUS_TOO_DISTANT = 5; // The command end time was too far in the future.
}
// Return status for the stream.
Status status = 2;
// Human-readable error description. Not for programmatic analysis.
string message = 3;
}