-
Notifications
You must be signed in to change notification settings - Fork 560
/
Copy pathrobot_command.proto
279 lines (237 loc) · 13 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
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
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
// 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.spot;
option java_outer_classname = "RobotCommandProto";
import "bosdyn/api/geometry.proto";
import "bosdyn/api/trajectory.proto";
import "google/protobuf/wrappers.proto";
// The locomotion hint specifying the gait of the robot.
enum LocomotionHint {
option allow_alias = true;
// Invalid; do not use.
HINT_UNKNOWN = 0;
// No hint, robot chooses an appropriate gait (typically trot.)
HINT_AUTO = 1;
// Most robust gait which moves diagonal legs together.
HINT_TROT = 2;
// Trot which comes to a stand when not commanded to move.
HINT_SPEED_SELECT_TROT = 3;
// Slow and steady gait which moves only one foot at a time.
HINT_CRAWL = 4;
// Crawl which comes to a stand when not commanded to move.
HINT_SPEED_SELECT_CRAWL = 10;
// Four beat gait where one foot touches down at a time.
HINT_AMBLE = 5;
// Amble which comes to a stand when not commanded to move.
HINT_SPEED_SELECT_AMBLE = 6;
// Demo gait which moves diagonal leg pairs together with an aerial phase.
HINT_JOG = 7;
// Demo gait which hops while holding some feet in the air.
HINT_HOP = 8;
// HINT_AUTO_TROT is deprecated due to the name being too similar to the Spot Autowalk feature.
// It has been replaced by HINT_SPEED_SELECT_TROT. Keeping this value in here for now for
// backwards compatibility, but this may be removed in future releases.
HINT_AUTO_TROT = 3;
// HINT_AUTO_AMBLE is deprecated due to the name being too similar to the Spot Autowalk feature.
// It has been replaced by HINT_SPEED_SELECT_AMBLE. Keeping this value in here for now for
// backwards compatibility, but this may be removed in future releases.
HINT_AUTO_AMBLE = 6;
}
// The type of swing height for a step.
enum SwingHeight {
SWING_HEIGHT_UNKNOWN = 0; // Invalid; do not use.
SWING_HEIGHT_LOW =
1; // Low-stepping. Robot will try to only swing legs a few cm away from ground.
SWING_HEIGHT_MEDIUM = 2; // Default for most cases, use other values with caution.
SWING_HEIGHT_HIGH = 3; // High-stepping. Possibly useful with degraded vision operation.
SWING_HEIGHT_AUTO = 4; // Swing height is automatically adjusted depending on the current state
// of the robot and environment.
}
// Params common across spot movement and mobility.
message MobilityParams {
// Max allowable velocity at any point in trajectory.
SE2VelocityLimit vel_limit = 1;
// Parameters for controlling Spot's body during motion.
BodyControlParams body_control = 2;
// Desired gait during locomotion
LocomotionHint locomotion_hint = 3;
// DEPRECATED as of 3.2.0: The boolean field has been replaced by the field stairs_mode.
// The following field will be deprecated and moved to 'reserved' in a future release.
bool stair_hint = 4 [deprecated = true];
// Stairs are only supported in trot gaits. Enabling stairs mode will override some user
// defaults in order to optimize stair behavior.
enum StairsMode {
STAIRS_MODE_UNKNOWN = 0; // Invalid; do not use.
STAIRS_MODE_OFF = 1;
STAIRS_MODE_ON = 2;
STAIRS_MODE_AUTO = 3; // Robot will automatically turn mode on or off.
STAIRS_MODE_PROHIBITED = 4; // Stairs will be detected and avoided.
}
// The selected option for stairs mode.
// If unset, will use the deprecated stair_hint instead.
// If falling back on stair_hint, false will map to STAIRS_MODE_OFF.
// This will be changed to STAIRS_MODE_AUTO in a future release.
StairsMode stairs_mode = 17;
// Allow the robot to move with degraded perception when there are perception faults.
bool allow_degraded_perception = 5;
// Control of obstacle avoidance.
ObstacleParams obstacle_params = 6;
// Swing height setting
SwingHeight swing_height = 7;
// Ground terrain parameters.
TerrainParams terrain_params = 8;
// Prevent the robot from using StairTracker even if in stairs mode.
bool disallow_stair_tracker = 9;
// Prevent the robot from automatically walking off a staircase in the case of an error
// (ex: e-stop settle_then_cut, critical battery level)
bool disable_stair_error_auto_descent = 16;
// Robot Body External Force parameters
BodyExternalForceParams external_force_params = 10;
// Prevent the robot from pitching to get a better look at rearward terrain except in stairs
// mode.
bool disallow_non_stairs_pitch_limiting = 11;
// Disable the secondary nearmap-based cliff avoidance that runs while on stairs.
bool disable_nearmap_cliff_avoidance = 12;
// When true, allows the robot to traverse large areas with no stereo data. When false, these
// regions of missing data are assumed to be cliffs which the robot avoids.
bool disable_missing_data_cliffs = 21;
// Semantic hazard detection can detect and classify objects or regions in the world as
// obstacles or areas to avoid that would not normally be classified as such. Obstacle avoidance
// still needs to be on for the robot to avoid these additional hazards. A CORE I/O is necessary
// for semantic hazard detection. Using HAZARD_DETECTION_MODE_COST will prevent detected hazards
// from becoming blocking obstacles, and instead add areas to try and avoid when navigating
// autonomously.
enum HazardDetectionMode {
HAZARD_DETECTION_MODE_UNKNOWN = 0;
HAZARD_DETECTION_MODE_OFF = 1;
HAZARD_DETECTION_MODE_ON = 2;
HAZARD_DETECTION_MODE_COST = 3;
}
// The selected option for hazard detection.
HazardDetectionMode hazard_detection_mode = 18;
}
// Parameters for offsetting the body from the normal default.
message BodyControlParams {
oneof param {
// Desired base offset relative to the footprint pseudo-frame.
// The footprint pseudo-frame is a gravity aligned frame with its origin located at the
// geometric center of the feet in the X-Y axis, and at the nominal height of the hips in
// the Z axis. The yaw of the frame (wrt the world) is calculated by the average foot
// locations, and is aligned with the feet.
SE3Trajectory base_offset_rt_footprint = 1;
// The base will adjust to assist with manipulation, adjusting its height, pitch, and yaw as
// a function of the hand's location. Note, manipulation assisted body control is only
// available for ArmCommand requests that control the end-effector, and are expressed in an
// inertial frame. For example, sending a ArmCartesianCommand request with root_frame_name
// set to "odom" will allow the robot to compute a body adjustment. However, sending a
// ArmCartesianCommand request with root_frame_name set to "body" or sending an
// ArmJointMoveCommand request is incompatible, and the body will reset to default height
// and orientation.
BodyAssistForManipulation body_assist_for_manipulation = 3;
// An absolute desired position and orientation of the robot body origin. Command may be
// saturated to achievable or safe postures on receipt. Note: This parameter only has effect
// when coupled with a StandCommand. For other commands, the robot will fall back to
// defaults.
BodyPose body_pose = 4;
}
// Setting for how the robot interprets base offset pitch & roll components.
// In the default case (ROTATION_SETTING_OFFSET) the robot will naturally align the body to the
// pitch of the current terrain. In some circumstances, the user may wish to override this value
// and try to maintain alignment with respect to gravity. Be careful with this setting as it may
// likely degrade robot performance in complex terrain, e.g. stairs, platforms, or slopes of
// sufficiently high grade.
enum RotationSetting {
ROTATION_SETTING_UNKNOWN = 0; // Invalid; do not use.
ROTATION_SETTING_OFFSET =
1; // Pitch & Roll are offset with respect to orientation of the footprint.
ROTATION_SETTING_ABSOLUTE = 2; // Pitch & Roll are offset with respect to gravity.
}
// The rotation setting for the robot body. Ignored if body_assist_for_manipulation or
// body_pose are enabled.
RotationSetting rotation_setting = 2;
// Instead of directly specify the base offset trajectory, these options allow the robot to
// calculate offsets based on the hand's location. If the robot does not have a SpotArm
// attached, sending this request will have no effect.
message BodyAssistForManipulation {
// Enable the use of body yaw to assist with manipulation.
bool enable_body_yaw_assist = 1;
// Enable use of hip height (e.g. body height/pitch) to assist with manipulation.
bool enable_hip_height_assist = 2;
}
// An SE3 based desired body pose trajectory with a specified base frame.
message BodyPose {
// The root frame for the desired pose, e.g. "vision" or "odom"
string root_frame_name = 1;
// The SE3 pose trajectory
SE3Trajectory base_offset_rt_root = 2;
}
}
// Parameters for obstacle avoidance types.
message ObstacleParams {
// Use vision to make the feet avoid obstacles by swinging higher?
bool disable_vision_foot_obstacle_avoidance = 1;
// Use vision to make the feet avoid constraints like edges of stairs?
bool disable_vision_foot_constraint_avoidance = 2;
// Use vision to make the body avoid obstacles?
bool disable_vision_body_obstacle_avoidance = 3;
// Desired padding around the body to use when attempting to avoid obstacles.
// Described in meters. Must be >= 0.
double obstacle_avoidance_padding = 4;
// Prevent the robot body from raising above nominal height to avoid lower-leg collisions with
// the terrain.
bool disable_vision_foot_obstacle_body_assist = 5;
// Use vision to make the robot avoid stepping into negative obstacles?
bool disable_vision_negative_obstacles = 6;
}
// Ground contact parameters that describe the terrain.
message TerrainParams {
// Terrain coefficient of friction user hint. This value must be positive and will be clamped if
// necessary on the robot side. Best suggested values lie in the range between 0.4 and 0.8
// (which is the robot's default.)
google.protobuf.DoubleValue ground_mu_hint = 2;
// *** Deprecation Warning ***
// DEPRECATED as of 3.0.0: The boolean field has been replaced by the field grated_surfaces_mode
// The following field will be deprecated and moved to 'reserved' in a future release.
bool enable_grated_floor = 3 [deprecated = true];
// Options for Grated Surfaces Mode. When Grated Surfaces Mode is on, the robot assumes the
// ground below it is made of grated metal or other repeated pattern. When on, the robot will
// make assumptions about the environment structure and more aggressively filter noise in
// perception data.
enum GratedSurfacesMode {
GRATED_SURFACES_MODE_UNKNOWN = 0; // Invalid; do not use.
GRATED_SURFACES_MODE_OFF = 1;
GRATED_SURFACES_MODE_ON = 2;
GRATED_SURFACES_MODE_AUTO = 3; // Robot will automatically turn mode on or off
}
// The selected option for grated surfaces mode
GratedSurfacesMode grated_surfaces_mode = 4;
}
// External Force on robot body parameters. This is a beta feature and still can have some odd
// behaviors. By default, the external force estimator is disabled on the robot.
message BodyExternalForceParams {
// Indicates what external force estimate/override the robot should use.
// By default, the external force estimator is disabled on the robot.
enum ExternalForceIndicator {
EXTERNAL_FORCE_NONE = 0; // No external forces considered.
EXTERNAL_FORCE_USE_ESTIMATE = 1; // Use external forces estimated by the robot
EXTERNAL_FORCE_USE_OVERRIDE = 2; // Use external forces specified in an override vector.
}
// The type of external force described by the parameters.
ExternalForceIndicator external_force_indicator = 1;
// The frame name for which the external_force_override is defined in. The frame must be known
// to the robot.
string frame_name = 4;
// Specifies a force that the body should expect to feel. This allows the robot to "lean into"
// an external force. Be careful using this override, since incorrect information can cause
// the robot to fall over.
// For example, if the robot is leaning against a wall in front of it, the force override would
// be in the negative x dimension. If the robot was pulling something directly behind it, the
// force override would be in the negative x dimension as well.
Vec3 external_force_override = 3;
// Reserved for deprecated fields.
reserved 2;
}