-
Notifications
You must be signed in to change notification settings - Fork 0
/
robot_state.proto
727 lines (583 loc) · 26.4 KB
/
robot_state.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
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
// Copyright (c) 2022 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 = "RobotStateProto";
import "bosdyn/api/geometry.proto";
import "bosdyn/api/header.proto";
import "bosdyn/api/parameter.proto";
import "bosdyn/api/service_fault.proto";
import "google/protobuf/timestamp.proto";
import "google/protobuf/duration.proto";
import "google/protobuf/wrappers.proto";
// Kinematic model of the robot skeleton.
message Skeleton {
// Each link of the robot skeleton.
message Link {
// The link name, which matches those used in the urdf.
string name = 1;
// Model to draw, expressed as an obj file.
// Note: To limit the size of responses, obj_file_contents might be omitted.
message ObjModel {
// Name of the file.
string file_name = 1;
// The contents of the file.
string file_contents = 2;
}
// The OBJ file representing the model of this link.
ObjModel obj_model = 2;
}
// The list of links that make up the robot skeleton.
repeated Link links = 2;
// URDF description of the robot skeleton.
string urdf = 3;
}
// Robot Hardware Configuration, described with the robot skeleton.
message HardwareConfiguration {
// Robot link and joint description.
Skeleton skeleton = 1;
// Set of power features that are compatible with the robot hardware.
// See power.proto for the associated requests.
bool can_power_command_request_off_robot = 2; // Turn off the robot. Same as physical switch.
bool can_power_command_request_cycle_robot = 3; // Power cycle the robot. Same as physical switch.
bool can_power_command_request_payload_ports = 4; // Control power to the payload ports.
bool can_power_command_request_wifi_radio = 5; // Control power to the hardware Wi-Fi radio.
}
// The current state of the robot.
message RobotState {
// Power state (e.g. motor power).
PowerState power_state = 1;
// Battery state (e.g. charge, temperature, current).
repeated BatteryState battery_states = 2;
// Communication state (e.g. type of comms network).
repeated CommsState comms_states = 3;
// Different system faults for the robot.
SystemFaultState system_fault_state = 4;
// Because there may be multiple E-Stops, and because E-Stops may be supplied with payloads,
// this is a repeated field instead of a hardcoded list.
repeated EStopState estop_states = 5;
// Kinematic state of the robot (e.g. positions, velocities, other frame information).
KinematicState kinematic_state = 6;
// Robot behavior fault state.
BehaviorFaultState behavior_fault_state = 7;
// The foot states (and contact information).
repeated FootState foot_state = 8;
/// State of the manipulator, only populated if an arm is attached to the robot.
ManipulatorState manipulator_state = 11;
// Service faults for services registered with the robot.
ServiceFaultState service_fault_state = 10;
// Relevant terrain data beneath and around the robot
TerrainState terrain_state = 12;
reserved 9;
}
// The power state for the robot.
// If a robot is not in the POWER OFF state, if is not safe to approach.
// The robot must not be E-Stopped to enter the POWER_ON state.
message PowerState {
// Robot clock timestamp corresponding to these readings.
google.protobuf.Timestamp timestamp = 1;
enum MotorPowerState {
option allow_alias = true;
// Unknown motor power state. Do not use this field.
STATE_UNKNOWN = 0 [deprecated = true];
MOTOR_POWER_STATE_UNKNOWN = 0;
// Motors are off, the robot is safe to approach.
STATE_OFF = 1 [deprecated = true];
MOTOR_POWER_STATE_OFF = 1;
// The motors are powered.
STATE_ON = 2 [deprecated = true];
MOTOR_POWER_STATE_ON = 2;
// The robot has received an ON command, and is turning on.
STATE_POWERING_ON = 3 [deprecated = true];
MOTOR_POWER_STATE_POWERING_ON = 3;
// In the process of powering down, not yet safe to approach.
STATE_POWERING_OFF = 4 [deprecated = true];
MOTOR_POWER_STATE_POWERING_OFF = 4;
// The robot is in an error state and must be powered off before attempting to re-power.
STATE_ERROR = 5 [deprecated = true];
MOTOR_POWER_STATE_ERROR = 5;
}
// The motor power state of the robot.
MotorPowerState motor_power_state = 2;
// State describing if robot is connected to shore (wall) power. Robot can't be powered on
// while on shore power
enum ShorePowerState {
option allow_alias = true;
// Unknown shore power state. Do not use.
STATE_UNKNOWN_SHORE_POWER = 0 [deprecated = true];
SHORE_POWER_STATE_UNKNOWN = 0;
// The robot is connected to shore power. The robot will not power on while connected to
// shore power.
STATE_ON_SHORE_POWER = 1 [deprecated = true];
SHORE_POWER_STATE_ON = 1;
// The robot is disconnected from shore power and motors can be powered up.
STATE_OFF_SHORE_POWER = 2 [deprecated = true];
SHORE_POWER_STATE_OFF = 2;
}
// The shore power state of the robot.
ShorePowerState shore_power_state = 3;
// State describing if the robot has power.
enum RobotPowerState {
// Unknown robot power state. Do not use this field.
ROBOT_POWER_STATE_UNKNOWN = 0;
// The robot is powered on.
ROBOT_POWER_STATE_ON = 1;
// The robot does not have power.
// Impossible to get this response, as the robot cannot respond if it is powered off.
ROBOT_POWER_STATE_OFF = 2;
}
// The payload ports power state of the robot.
RobotPowerState robot_power_state = 6;
// State describing if the payload port has power.
enum PayloadPortsPowerState {
// Unknown payload port power state. Do not use this field.
PAYLOAD_PORTS_POWER_STATE_UNKNOWN = 0;
// The payload port is powered on.
PAYLOAD_PORTS_POWER_STATE_ON = 1;
// The payload port does not have power.
PAYLOAD_PORTS_POWER_STATE_OFF = 2;
}
// The payload ports power state of the robot.
PayloadPortsPowerState payload_ports_power_state = 7;
// State describing if the robot Wi-Fi router has power.
enum WifiRadioPowerState {
// Unknown radio power state. Do not use this field.
WIFI_RADIO_POWER_STATE_UNKNOWN = 0;
// The radio is powered on.
WIFI_RADIO_POWER_STATE_ON = 1;
// The radio does not have power.
WIFI_RADIO_POWER_STATE_OFF = 2;
}
// The hardware radio power state of the robot.
WifiRadioPowerState wifi_radio_power_state = 9;
// Number from 0 (empty) to 100 (full) indicating the estimated state of charge.
// This field provides a summary of the BatteryStates that provide power for motor and/or
// base compute power, both of which are required for locomotion.
google.protobuf.DoubleValue locomotion_charge_percentage = 4;
// An estimate of remaining runtime. Note that this field might not be populated.
// This field provides a summary of the BatteryStates that provide power for motor and/or
// base compute power, both of which are required for locomotion.
google.protobuf.Duration locomotion_estimated_runtime = 5;
}
// The current state of each system fault the robot is experiencing.
// An "active" fault indicates a hardware/software currently on the robot.
// A "historical" fault indicates a, now cleared, hardware/software problem.
// Historical faults are useful to diagnose robot behavior subject to intermittent failed states.
message SystemFaultState {
// Currently active faults
repeated SystemFault faults = 1;
// Inactive faults that cleared within the last 10 minutes
repeated SystemFault historical_faults = 2;
// Aggregated fault data.
// This provides a very quick way of determining if there any
// "battery" or "vision" faults above a certain severity level.
map<string, SystemFault.Severity> aggregated = 3;
}
// The current system faults for a robot.
// A fault is an indicator of a hardware or software problem on the robot. An
// active fault may indicate the robot may fail to comply with a user request.
// The exact response a fault may vary, but possible responses include: failure
// to enable motor power, loss of perception enabled behavior, or triggering a
// fault recovery behavior on robot.
message SystemFault {
// Name of the fault.
string name = 1;
// Time of robot local clock at fault onset.
google.protobuf.Timestamp onset_timestamp = 2;
// Time elapsed since onset of the fault.
google.protobuf.Duration duration = 3;
// Error code returned by a fault. The exact interpretation of the fault code
// is unique to each variety of fault on the robot. The code is useful for
// Boston Dynamics support staff to diagnose hardware/software issues on
// robot.
int32 code = 4;
// Fault UID
uint64 uid = 8;
// User visible description of the fault (and possibly remedies.)
string error_message = 5;
// Fault attributes
// Each fault may be flagged with attribute metadata (strings in this case.)
// These attributes are useful to communicate that a particular fault may
// have significant effect on robot operations. Some potential attributes
// may be "robot", "imu", "vision", or "battery". These attributes would let
// us flag a fault as indicating a problem with the base robot hardware,
// gyro, perception system, or battery respectively. A fault may have, zero,
// one, or more attributes attached to it, i.e. a "battery" fault may also
// be considered a "robot" fault.
repeated string attributes = 6;
enum Severity {
// Unknown severity
SEVERITY_UNKNOWN = 0;
// No hardware problem
SEVERITY_INFO = 1;
// Robot performance may be degraded
SEVERITY_WARN = 2;
// Critical fault
SEVERITY_CRITICAL = 3;
}
// Fault severity, how bad is the fault?
// The severity level will have some indication of the potential robot
// response to the fault. For example, a fault marked with "battery"
// attribute and severity level SEVERITY_WARN may indicate a low battery
// state of charge. However a "battery" fault with severity level
// SEVERITY_CRITICAL likely means the robot is going to shutdown
// immediately.
Severity severity = 7;
}
// The robot's current E-Stop states and endpoints.
// A typical robot has several different E-Stops, all which must be "NOT_ESTOPPED"
// in order to run the robot.
message EStopState {
// Robot clock timestamp corresponding to these readings.
google.protobuf.Timestamp timestamp = 1;
// Name of the E-Stop
string name = 2;
enum Type {
// Unknown type of E-Stop. Do not use this field.
TYPE_UNKNOWN = 0;
// E-Stop is a physical button
TYPE_HARDWARE = 1;
// E-Stop is a software process
TYPE_SOFTWARE = 2;
}
// What kind of E-Stop this message describes.
Type type = 3;
enum State {
// No E-Stop information is present. Only happens in an error case.
STATE_UNKNOWN = 0;
// E-Stop is active -- robot cannot power its actuators.
STATE_ESTOPPED = 1;
// E-Stop is released -- robot may be able to power its actuators.
STATE_NOT_ESTOPPED = 2;
}
// The state of the E-Stop (is it E-Stopped or not?)
State state = 4;
// Optional description of E-Stop status.
string state_description = 5;
}
// The battery state for the robot. This includes information about the charge or the
// battery temperature.
message BatteryState {
// Robot clock timestamp corresponding to these readings.
google.protobuf.Timestamp timestamp = 1;
// An identifier for this battery (could be a serial number or a name. subject to change).
string identifier = 2;
// Number from 0 (empty) to 100 (full) indicating the estimated state of charge of the battery.
google.protobuf.DoubleValue charge_percentage = 3;
// An estimate of remaining runtime. Note that this field might not be populated.
google.protobuf.Duration estimated_runtime = 4;
// Measured current into (charging, positive) or out of (discharging, negative) the battery in
// Amps.
google.protobuf.DoubleValue current = 5;
// Measured voltage of the entire battery in Volts.
google.protobuf.DoubleValue voltage = 6;
// Measured temperature measurements of battery, in Celsius.
// Temperatures may be measured in many locations across the battery.
repeated double temperatures = 7;
enum Status {
// The battery is in an unknown / unexpected state.
STATUS_UNKNOWN = 0;
// The battery is not plugged in or otherwise not talking.
STATUS_MISSING = 1;
// The battery is plugged in to shore power and charging.
STATUS_CHARGING = 2;
// The battery is not plugged into shore power and discharging.
STATUS_DISCHARGING = 3;
// The battery was just plugged in and is booting up= 3;
STATUS_BOOTING = 4;
}
// Current state of the battery.
Status status = 8;
}
// The kinematic state of the robot describes the current estimated positions of the robot body and joints throughout the world.
// It includes a transform snapshot of the robot’s current known frames as well as joint states and the velocity of the body.
message KinematicState {
// Joint state of all robot joints.
repeated JointState joint_states = 2;
// Robot clock timestamp corresponding to these readings.
google.protobuf.Timestamp acquisition_timestamp = 30;
// A tree-based collection of transformations, which will include the transformations to the
// robot body ("body") in addition to transformations to the common frames ("world", "dr") and
// ground plane estimate "gpe".
// All transforms within the snapshot are at the acquisition time of kinematic state.
FrameTreeSnapshot transforms_snapshot = 31;
// Velocity of the body frame with respect to vision frame and expressed in vision frame.
// The linear velocity is applied at the origin of the body frame.
SE3Velocity velocity_of_body_in_vision = 8;
// Velocity of the body frame with respect to odom frame and expressed in odom frame.
// Again, the linear velocity is applied at the origin of the body frame.
SE3Velocity velocity_of_body_in_odom = 12;
// Previous fields in the protobuf that are now reserved.
reserved 1, 3, 4, 5, 6, 9, 10, 11;
}
// Proto containing the state of a joint on the robot. This can be used with the robot skeleton to
// update the current view of the robot.
message JointState {
// This name maps directly to the joints in the URDF.
string name = 1;
// This is typically an angle in radians as joints are typically revolute. However, for
// translational joints this could be a distance in meters.
google.protobuf.DoubleValue position = 2;
// The joint velocity in [m/s].
google.protobuf.DoubleValue velocity = 3;
// The joint acceleration in [m/s^2].
google.protobuf.DoubleValue acceleration = 4;
// This is typically a torque in Newton meters as joints are typically revolute. However, for
// translational joints this could be a force in Newtons.
google.protobuf.DoubleValue load = 5;
}
// This describes any current behaviror faults on the robot, which would block any robot commands
// from going through. These can be cleared using the ClearBehaviorFault rpc in the robot command
// service.
message BehaviorFaultState {
// Current errors potentially blocking commands on robot
repeated BehaviorFault faults = 1;
}
// The details of what the behavior fault consistents of, and the id for the fault. The unique
// behavior_fault_id can be used to clear the fault in robot command service ClearBehaviorFault rpc.
message BehaviorFault {
// Behavior fault unique id
uint32 behavior_fault_id = 1;
// Time of robot local clock at time of the error
google.protobuf.Timestamp onset_timestamp = 2;
enum Cause {
// Unknown cause of error
CAUSE_UNKNOWN = 0;
// Error caused by mobility failure or fall
CAUSE_FALL = 1;
// Error caused by robot hardware malfunction
CAUSE_HARDWARE = 2;
/// A lease has timed out
CAUSE_LEASE_TIMEOUT = 3;
}
// The potential cause of the fault.
Cause cause = 3;
enum Status {
// Unknown clearable status
STATUS_UNKNOWN = 0;
// Fault is clearable
STATUS_CLEARABLE = 1;
// Fault is currently not clearable
STATUS_UNCLEARABLE = 2;
}
// Information about the status/what can be done with the fault.
Status status = 4;
}
// Key robot metrics (e.g., Gait cycles (count), distance walked, time moving, etc...).
message RobotMetrics {
// Robot timestamp corresponding to these metrics.
google.protobuf.Timestamp timestamp = 1;
// Key tracked robot metrics, such as distance walked, runtime, etc.
repeated Parameter metrics = 2;
}
// The current comms information, including what comms the robot is using and the current status
// of the comms network.
message CommsState {
// Robot timestamp corresponding to these readings.
google.protobuf.Timestamp timestamp = 1;
oneof state {
// The communication state is WiFi.
WiFiState wifi_state = 2;
}
}
message WiFiState {
enum Mode {
// The robot's comms state is unknown, or no user requested mode.
MODE_UNKNOWN = 0;
// The robot is acting as an access point.
MODE_ACCESS_POINT = 1;
// The robot is connected to a network.
MODE_CLIENT = 2;
}
// Current WiFi mode.
Mode current_mode = 1;
// Essid of robot (master mode) or connected network.
string essid = 2;
}
// Information about the foot positions and contact state, on a per-foot basis.
message FootState {
// The foot position described relative to the body.
Vec3 foot_position_rt_body = 1;
enum Contact {
// Unknown contact. Do not use.
CONTACT_UNKNOWN = 0;
// The foot is currently in contact with the ground.
CONTACT_MADE = 1;
// The foot is not in contact with the ground.
CONTACT_LOST = 2;
}
// Is the foot in contact with the ground?
Contact contact = 2;
// Foot specific terrain data. Data may not be valid if the contact state is
// not CONTACT_MADE.
message TerrainState {
// Estimated ground coefficient of friction for this foot.
double ground_mu_est = 1;
// Reference frame name for vector data.
string frame_name = 2;
// Foot slip distance rt named frame
Vec3 foot_slip_distance_rt_frame = 3;
// Foot slip velocity rt named frame
Vec3 foot_slip_velocity_rt_frame = 4;
// Ground contact normal rt named frame
Vec3 ground_contact_normal_rt_frame = 5;
// Mean penetration (meters) of the foot below the ground visual
// surface. For penetrable terrains (gravel/sand/grass etc.) these values are
// positive. Negative values would indicate potential odometry issues.
double visual_surface_ground_penetration_mean = 6;
// Standard deviation of the visual surface ground penetration.
double visual_surface_ground_penetration_std = 7;
}
TerrainState terrain = 3;
}
/// Additional state published if an arm is attached to the robot.
message ManipulatorState {
// How open the gripper is, measured in percent.
// 0 = fully closed, 100 = fully open.
double gripper_open_percentage = 12;
/// Will be true if the gripper is holding an item, false otherwise.
bool is_gripper_holding_item = 6;
// The estimated force on the end-effector expressed in the hand frame.
Vec3 estimated_end_effector_force_in_hand = 13;
enum StowState {
STOWSTATE_UNKNOWN = 0;
STOWSTATE_STOWED = 1;
STOWSTATE_DEPLOYED = 2;
}
/// Information on if the arm is stowed, or deployed.
StowState stow_state = 9;
// Velocity of the hand frame with respect to vision frame and expressed in vision frame.
// The linear velocity is applied at the origin of the hand frame.
SE3Velocity velocity_of_hand_in_vision = 14;
// Velocity of the hand frame with respect to odom frame and expressed in odom frame.
// Again, the linear velocity is applied at the origin of the hand frame.
SE3Velocity velocity_of_hand_in_odom = 15;
// The stowing behavior is modified as a function of the Carry State. If holding an item, the
// stowing behavior will be modified as follows:
// NOT_CARRIABLE - The arm will not stow, instead entering stop
// CARRIABLE - The arm will not stow, instead entering stop
// CARRIABLE_AND_STOWABLE - The arm will stow while continuing to grasp the item
// The comms loss behavior of the arm is also modified as follows:
// NOT_CARRIABLE - The arm will release the item and stow
// CARRIABLE - The arm will not stow, instead entering stop
// CARRIABLE_AND_STOWABLE - The arm will stow while continuing to grasp the item
enum CarryState {
CARRY_STATE_UNKNOWN = 0;
CARRY_STATE_NOT_CARRIABLE = 1;
CARRY_STATE_CARRIABLE = 2;
CARRY_STATE_CARRIABLE_AND_STOWABLE = 3;
}
CarryState carry_state = 16;
// Previous fields in the protobuf that are now reserved.
reserved 1, 2, 3, 4, 5, 7, 8, 10, 11;
}
// The current state of each service fault the robot is experiencing.
// An "active" fault indicates a fault currently in a service.
// A "historical" fault indicates a, now cleared, service problem.
message ServiceFaultState {
// Currently active faults
repeated ServiceFault faults = 1;
// Service faults that have been cleared. Acts as a ring buffer with size of 50.
repeated ServiceFault historical_faults = 2;
// Aggregated service fault data. Maps attribute string to highest severity level
// of any active fault containing that attribute string.
// This provides a very quick way of determining if there any "locomotion" or
// "vision" faults above a certain severity level.
map<string, ServiceFault.Severity> aggregated = 3;
}
// Relevant terrain data beneath and around the robot
message TerrainState {
// Is the terrain immediately under the robot such that sitting or powering off
// the robot may cause the robot to be in an unstable position?
bool is_unsafe_to_sit = 1;
}
// The RobotState request message to get the current state of the robot.
message RobotStateRequest {
// Common request header.
RequestHeader header = 1;
}
// The RobotState response message, which returns the robot state information from the time
// the request was received.
message RobotStateResponse {
// Common response header.
ResponseHeader header = 1;
// The requested RobotState.
RobotState robot_state = 2;
}
// The RobotMetrics request message to get metrics and parameters from the robot.
message RobotMetricsRequest {
// Common request header.
RequestHeader header = 1;
}
// The RobotMetrics response message, which returns the metrics information from the time
// the request was received.
message RobotMetricsResponse {
// Common response header.
ResponseHeader header = 1;
// The requested robot metrics.
RobotMetrics robot_metrics = 2;
}
// The RobotHardwareConfiguration request message to get hardware configuration, described
// by the robot skeleton and urdf.
message RobotHardwareConfigurationRequest {
// Common request header.
RequestHeader header = 1;
}
// The RobotHardwareConfiguration response message, which returns the hardware config from the time
// the request was received.
message RobotHardwareConfigurationResponse {
// Common response header.
ResponseHeader header = 1;
// The requested RobotState.
HardwareConfiguration hardware_configuration = 2;
}
// The RobotLinkModel request message uses a link name returned by the RobotHardwareConfiguration response to
// get the associated OBJ file.
message RobotLinkModelRequest {
// Common request header.
RequestHeader header = 1;
// The link name of which the OBJ file shoould represent.
string link_name = 2;
}
// The RobotLinkModel response message returns the OBJ file for a specifc robot link.
message RobotLinkModelResponse {
// Common response header.
ResponseHeader header = 1;
// The requested RobotState skeleton obj model.
Skeleton.Link.ObjModel link_model = 2;
}
// Keeps track of why the robot is not able to drive autonomously.
message RobotImpairedState {
// If the robot is stopped due to being impaired, this is the reason why.
enum ImpairedStatus {
// Unknown/unexpected error.
IMPAIRED_STATUS_UNKNOWN = 0;
// The robot is able to drive.
IMPAIRED_STATUS_OK = 1;
// The autonomous system does not have any data from the robot state service.
IMPAIRED_STATUS_NO_ROBOT_DATA = 2;
// There is a system fault which caused the robot to stop. See system_fault for details.
IMPAIRED_STATUS_SYSTEM_FAULT = 3;
// The robot's motors are not powered on.
IMPAIRED_STATUS_NO_MOTOR_POWER = 4;
// The autonomous system is expected to have a remote point cloud (e.g. a LIDAR), but this is not working.
IMPAIRED_STATUS_REMOTE_CLOUDS_NOT_WORKING = 5;
// A remote service the autonomous system depends on is not working.
IMPAIRED_STATUS_SERVICE_FAULT = 6;
// A behavior fault caused the robot to stop. See behavior_faults for details.
IMPAIRED_STATUS_BEHAVIOR_FAULT = 7;
}
// If the status is ROBOT_IMPAIRED, this is specifically why the robot is impaired.
ImpairedStatus impaired_status = 1;
// If impaired_status is STATUS_SYSTEM_FAULT, these are the faults which caused the robot to stop.
repeated bosdyn.api.SystemFault system_faults = 2;
// If impaired_status is STATUS_SERVICE_FAULT, these are the service faults which caused
// the robot to stop.
repeated bosdyn.api.ServiceFault service_faults = 3;
// If impaired_status is STATUS_BEHAVIOR_FAULT, these are the behavior faults which caused
// the robot to stop.
repeated bosdyn.api.BehaviorFault behavior_faults = 4;
}