-
Notifications
You must be signed in to change notification settings - Fork 598
Expand file tree
/
Copy pathrobot_command.py
More file actions
2181 lines (1829 loc) · 106 KB
/
robot_command.py
File metadata and controls
2181 lines (1829 loc) · 106 KB
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
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# 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).
"""For clients to the robot command service."""
import collections
import time
from bosdyn.api import (arm_command_pb2, basic_command_pb2, full_body_command_pb2, geometry_pb2,
mobility_command_pb2, payload_estimation_pb2, robot_command_pb2,
robot_command_service_pb2_grpc, synchronized_command_pb2, trajectory_pb2)
# isort: off
# isort: on
from google.protobuf import any_pb2, wrappers_pb2
from bosdyn import geometry
from bosdyn.api.spot import robot_command_pb2 as spot_command_pb2
from bosdyn.client.common import (BaseClient, error_factory, error_pair,
handle_common_header_errors, handle_lease_use_result_errors,
handle_unset_status_error)
from bosdyn.util import now_sec, seconds_to_duration
from .exceptions import Error as BaseError
from .exceptions import InvalidRequestError, ResponseError, TimedOutError, UnsetStatusError
from .frame_helpers import BODY_FRAME_NAME, ODOM_FRAME_NAME, get_se2_a_tform_b
from .lease import add_lease_wallet_processors
from .math_helpers import SE2Pose, SE3Pose
# The angles (in radians) that represent the claw gripper open and closed positions.
_CLAW_GRIPPER_OPEN_ANGLE = -1.5708
_CLAW_GRIPPER_CLOSED_ANGLE = 0
class RobotCommandResponseError(ResponseError):
"""General class of errors for RobotCommand service."""
class Error(BaseError):
"""Base class for non-response errors in this module."""
class NoTimeSyncError(RobotCommandResponseError):
"""Client has not done timesync with robot."""
class ExpiredError(RobotCommandResponseError):
"""The command was received after its max_duration had already passed."""
class TooDistantError(RobotCommandResponseError):
"""The command end time was too far in the future."""
class NotPoweredOnError(RobotCommandResponseError):
"""The robot must be powered on to accept a command."""
class BehaviorFaultError(RobotCommandResponseError):
"""The robot may not be commanded with uncleared behavior faults."""
class DockedError(RobotCommandResponseError):
"""The command cannot be executed while the robot is docked."""
class NotClearedError(RobotCommandResponseError):
"""Behavior fault could not be cleared."""
class UnsupportedError(RobotCommandResponseError):
"""The API supports this request, but the system does not support this request."""
class CommandFailedError(Error):
"""Command indicated it failed in its feedback."""
class CommandFailedErrorWithFeedback(CommandFailedError):
"""Command indicated it failed in its feedback.
This subclass contains the feedback response causing the error.
"""
def __init__(self, message, feedback):
super().__init__(message)
self.feedback = feedback
class CommandTimedOutError(Error):
"""Timed out waiting for SUCCESS response from robot command."""
class UnknownFrameError(RobotCommandResponseError):
"""Robot does not know how to handle supplied frame."""
class _TimeConverter(object):
"""Constructs a RobotTimeConverter as necessary.
Args:
parent: Parent for the time sync endpoint.
endpoint: Endpoint for the time converted.
"""
def __init__(self, parent, endpoint):
self._parent = parent
self._endpoint = endpoint
self._converter = None
@property
def obj(self):
"""Accessor which lazily constructs the RobotTimeConverter."""
if not self._converter:
endpoint = self._endpoint or self._parent.timesync_endpoint
self._converter = endpoint.get_robot_time_converter()
return self._converter
def convert_timestamp_from_local_to_robot(self, timestamp):
"""Calls RobotTimeConverter.convert_timestamp_from_local_to_robot().
Args:
timestamp: Timestamp to convert.
"""
self.obj.convert_timestamp_from_local_to_robot(timestamp)
def robot_timestamp_from_local_secs(self, end_time_secs):
"""Calls RobotTimeConverter.robot_timestamp_from_local_secs().
Args:
end_time_secs: Time in seconds to convert.
"""
return self.obj.robot_timestamp_from_local_secs(end_time_secs)
def local_seconds_from_robot_timestamp(self, robot_timestamp):
"""Calls RobotTimeConverter.local_seconds_from_robot_timestamp().
Args:
local_time_secs: Local system time, in seconds from the unix epoch.
"""
return self.obj.local_seconds_from_robot_timestamp(robot_timestamp)
# Tree of proto-fields leading to end_time fields needing to be set from end_time_secs.
END_TIME_EDIT_TREE = {
'synchronized_command': {
'mobility_command': {
'@command': { # 'command' is a oneof submessage
'se2_velocity_request': {
'end_time': None
},
'se2_trajectory_request': {
'end_time': None
},
'stance_request': {
'end_time': None
}
}
},
'arm_command': {
'@command': { # 'command' is a oneof submessage
'arm_velocity_command': {
'end_time': None
}
}
}
}
}
# Tree of proto fields leading to Timestamp protos which need to be converted from
# client clock to robot clock values using timesync information from the robot.
# Note, the "@" sign indicates a oneof field. The "None" indicates the field which
# contains the timestamp to be updated.
EDIT_TREE_CONVERT_LOCAL_TIME_TO_ROBOT_TIME = {
'synchronized_command': {
'mobility_command': {
'@command': {
'se2_trajectory_request': {
'trajectory': {
'reference_time': None
}
},
}
},
'gripper_command': {
'@command': {
'claw_gripper_command': {
'trajectory': {
'reference_time': None
}
}
}
},
'arm_command': {
'@command': {
'arm_cartesian_command': {
'pose_trajectory_in_task': {
'reference_time': None
},
'wrench_trajectory_in_task': {
'reference_time': None
}
},
'arm_joint_move_command': {
'trajectory': {
'reference_time': None
}
},
'arm_gaze_command': {
'target_trajectory_in_frame1': {
'reference_time': None
},
'tool_trajectory_in_frame2': {
'reference_time': None
}
},
'arm_impedance_command': {
'task_tform_desired_tool': {
'reference_time': None
},
}
}
}
}
}
# Tree of proto fields leading to Timestamp protos which need to be converted from
# client clock to robot clock values using timesync information from the robot.
# Note, the "@" sign indicates a oneof field. The "None" indicates the field which
# contains the timestamp to be updated.
MOBILITY_PARAM_TREE_CONVERT_LOCAL_TIME_TO_ROBOT_TIME = {
'body_control': {
'@param': {
'base_offset_rt_footprint': {
'reference_time': None
},
'body_pose': {
'base_offset_rt_root': {
'reference_time': None
}
}
}
}
}
def _edit_proto(proto, edit_tree, edit_fn):
"""Recursion to update specified fields of a protobuf using a specified edit-function.
Args:
proto: Protobuf to edit recursively.
edit_tree: Part of the tree to edit.
edit_fn: Edit function to execute.
"""
for key, subtree in edit_tree.items():
if key.startswith('@'):
# Recursion into a one-of message. '@key' means field 'key' contains a one-of message.
which_oneof = proto.WhichOneof(key[1:])
if not which_oneof or which_oneof not in subtree:
# No submessage, or tree doesn't contain a conversion for it.
return
_edit_proto(getattr(proto, which_oneof), subtree[which_oneof], edit_fn)
elif subtree:
# Recursion into a sub-message by field name.
if key in proto.DESCRIPTOR.fields_by_name and proto.HasField(key):
subproto = getattr(proto, key)
_edit_proto(subproto, subtree, edit_fn)
else:
# At a leaf node of the edit_tree. Edit the proto using the supplied function.
edit_fn(key, proto)
class RobotCommandClient(BaseClient):
"""Client for calling RobotCommand services."""
default_service_name = 'robot-command'
service_type = 'bosdyn.api.RobotCommandService'
def __init__(self):
super(RobotCommandClient,
self).__init__(robot_command_service_pb2_grpc.RobotCommandServiceStub)
self._timesync_endpoint = None
def update_from(self, other):
"""Update instance from another object.
Args:
other: The object where to copy from.
"""
super(RobotCommandClient, self).update_from(other)
if self.lease_wallet:
add_lease_wallet_processors(self, self.lease_wallet)
# Grab a timesync endpoint if it is available.
try:
self._timesync_endpoint = other.time_sync.endpoint
except AttributeError:
pass # other doesn't have a time_sync accessor
@property
def timesync_endpoint(self):
"""Accessor for timesync-endpoint that was grabbed via 'update_from()'."""
if not self._timesync_endpoint:
raise NoTimeSyncError(
response=None,
error_message="No timesync endpoint was passed to robot command client.")
return self._timesync_endpoint
def robot_command(self, command, end_time_secs=None, timesync_endpoint=None, lease=None,
**kwargs):
"""Issue a command to the robot synchronously.
Args:
command: Command to issue.
end_time_secs: End time for the command in seconds.
timesync_endpoint: Timesync endpoint.
lease: Lease object to use for the command.
Returns:
ID of the issued robot command.
Raises:
RpcError: Problem communicating with the robot.
bosdyn.client.exceptions.InvalidRequestError: Invalid request received by the robot.
UnsupportedError: The API supports this request, but the system does not support this
request.
bosdyn.client.robot_command.NoTimeSyncError: Client has not done timesync with robot.
ExpiredError: The command was received after its max_duration had already passed.
bosdyn.client.robot_command.TooDistantError: The command end time was too far in the future.
NotPoweredOnError: The robot must be powered on to accept a command.
BehaviorFaultError: The robot is faulted and the fault must be cleared first.
DockedError: The command cannot be executed while the robot is docked.
bosdyn.client.robot_command.UnknownFrameError: Robot does not know how to handle supplied frame.
"""
req = self._get_robot_command_request(lease, command)
# Update req.command instead of command so that we don't modify an input in this function.
self._update_command_timestamps(req.command, end_time_secs, timesync_endpoint)
return self.call(self._stub.RobotCommand, req, _robot_command_value, _robot_command_error,
copy_request=False, **kwargs)
def robot_command_async(self, command, end_time_secs=None, timesync_endpoint=None, lease=None,
**kwargs):
"""Async version of robot_command().
Args:
command: Command to issue.
end_time_secs: End time for the command in seconds.
timesync_endpoint: Timesync endpoint.
lease: Lease object to use for the command.
Returns:
ID of the issued robot command.
Raises:
RpcError: Problem communicating with the robot.
bosdyn.client.exceptions.InvalidRequestError: Invalid request received by the robot.
UnsupportedError: The API supports this request, but the system does not support this
request.
bosdyn.client.robot_command.NoTimeSyncError: Client has not done timesync with robot.
ExpiredError: The command was received after its max_duration had already passed.
bosdyn.client.robot_command.TooDistantError: The command end time was too far in the future.
NotPoweredOnError: The robot must be powered on to accept a command.
bosdyn.client.robot_command.UnknownFrameError: Robot does not know how to handle supplied frame.
"""
req = self._get_robot_command_request(lease, command)
# Update req.command instead of command so that we don't modify an input to this function.
self._update_command_timestamps(req.command, end_time_secs, timesync_endpoint)
return self.call_async(self._stub.RobotCommand, req, _robot_command_value,
_robot_command_error, copy_request=False, **kwargs)
def robot_command_feedback(self, robot_command_id=None, **kwargs):
"""Get feedback from a previously issued command.
Args:
robot_command_id: ID of the robot command to get feedback on. If blank, will return feedback for the
current active command if a command is in progress.
Raises:
RpcError: Problem communicating with the robot.
"""
req = self._get_robot_command_feedback_request(robot_command_id)
return self.call(self._stub.RobotCommandFeedback, req, None, _robot_command_feedback_error,
copy_request=False, **kwargs)
def robot_command_feedback_async(self, robot_command_id=None, **kwargs):
"""Async version of robot_command_feedback().
Args:
robot_command_id: ID of the robot command to get feedback on.
Raises:
RpcError: Problem communicating with the robot.
"""
req = self._get_robot_command_feedback_request(robot_command_id)
return self.call_async(self._stub.RobotCommandFeedback, req, None,
_robot_command_feedback_error, copy_request=False, **kwargs)
def clear_behavior_fault(self, behavior_fault_id, lease=None, **kwargs):
"""Clear a behavior fault on the robot.
Args:
behavior_fault_id: ID of the behavior fault.
lease: Lease information to use in the message.
Returns:
Boolean whether response status is STATUS_CLEARED.
Raises:
RpcError: Problem communicating with the robot.
NotClearedError: Behavior fault could not be cleared.
"""
req = self._get_clear_behavior_fault_request(lease, behavior_fault_id)
return self.call(self._stub.ClearBehaviorFault, req, _clear_behavior_fault_value,
_clear_behavior_fault_error, copy_request=False, **kwargs)
def clear_behavior_fault_async(self, behavior_fault_id, lease=None, **kwargs):
"""Async version of clear_behavior_fault().
Args:
behavior_fault_id:
lease:
behavior_fault_id: ID of the behavior fault.
lease: Lease information to use in the message.
Returns:
Boolean whether response status is STATUS_CLEARED.
Raises:
RpcError: Problem communicating with the robot.
NotClearedError: Behavior fault could not be cleared.
"""
req = self._get_clear_behavior_fault_request(lease, behavior_fault_id)
return self.call_async(self._stub.ClearBehaviorFault, req, _clear_behavior_fault_value,
_clear_behavior_fault_error, copy_request=False, **kwargs)
def _get_robot_command_request(self, lease, command):
"""Create RobotCommandRequest message from the given information.
Args:
lease: Lease to use for the command.
command: Command to specify in the request message.
Returns:
Filled out RobotCommandRequest message.
"""
return robot_command_pb2.RobotCommandRequest(
lease=lease, command=command, clock_identifier=self.timesync_endpoint.clock_identifier)
def _update_command_timestamps(self, command, end_time_secs, timesync_endpoint):
"""Set or convert fields of the command proto that need timestamps in the robot's clock.
Args:
command: Command message to update.
end_time_secs: Command end time in seconds.
timesync_endpoint: Timesync endpoint.
"""
# Lazy RobotTimeConverter: initialized only if needed to make a conversion.
converter = _TimeConverter(self, timesync_endpoint)
def _set_end_time(key, proto):
"""If proto has a field named key, fill set it to end_time_secs as robot time. """
if key not in proto.DESCRIPTOR.fields_by_name:
return # No such field in the proto to be set to the end-time.
end_time = getattr(proto, key)
end_time.CopyFrom(converter.robot_timestamp_from_local_secs(end_time_secs))
def _to_robot_time(key, proto):
"""If proto has a field named key with a timestamp, convert timestamp to robot time."""
if not (key in proto.DESCRIPTOR.fields_by_name and proto.HasField(key)):
# No such field in proto, or field does not contain a timestamp.
return
timestamp = getattr(proto, key)
converter.convert_timestamp_from_local_to_robot(timestamp)
# Set fields needing to be set from end_time_secs.
if end_time_secs:
_edit_proto(command, END_TIME_EDIT_TREE, _set_end_time)
# Convert timestamps from local time to robot time.
_edit_proto(command, EDIT_TREE_CONVERT_LOCAL_TIME_TO_ROBOT_TIME, _to_robot_time)
if command.synchronized_command.mobility_command.HasField("params"):
params = spot_command_pb2.MobilityParams()
command.synchronized_command.mobility_command.params.Unpack(params)
_edit_proto(params, MOBILITY_PARAM_TREE_CONVERT_LOCAL_TIME_TO_ROBOT_TIME,
_to_robot_time)
command.synchronized_command.mobility_command.params.Pack(params)
@staticmethod
def _get_robot_command_feedback_request(robot_command_id):
"""Create RobotCommandFeedbackRequest message with the given command id.
Args:
robot_command_id: Command id to specify in the request message.
Returns:
Filled out RobotCommandFeedbackRequest message.
"""
return robot_command_pb2.RobotCommandFeedbackRequest(robot_command_id=robot_command_id)
@staticmethod
def _get_clear_behavior_fault_request(lease, behavior_fault_id):
"""Create ClearBehaviorFaultRequest message with the given information.
Args:
lease: Lease information to use in the request.
behavior_fault_id: Fault id to specify in the request message.
Returns:
Filled out ClearBehaviorFaultRequest message.
"""
return robot_command_pb2.ClearBehaviorFaultRequest(lease=lease,
behavior_fault_id=behavior_fault_id)
class RobotCommandStreamingClient(BaseClient):
"""Client for calling RobotCommand services.
This client is in BETA and may undergo changes in future releases.
"""
default_service_name = 'robot-command-streaming'
service_type = 'bosdyn.api.RobotCommandStreamingService'
def __init__(self):
super(RobotCommandStreamingClient,
self).__init__(robot_command_service_pb2_grpc.RobotCommandStreamingServiceStub)
self._timesync_endpoint = None
def send_joint_control_commands(self, command_iterator):
return self._stub.JointControlStream(command_iterator)
def _robot_command_value(response):
"""Get the command id from a RobotCommandResponse.
Args:
response: RobotCommandResponse message.
Returns:
Robot Command id in the response message.
"""
return response.robot_command_id
# yapf: disable
_ROBOT_COMMAND_STATUS_TO_ERROR = collections.defaultdict(
lambda: (RobotCommandResponseError, None))
_ROBOT_COMMAND_STATUS_TO_ERROR.update({
robot_command_pb2.RobotCommandResponse.STATUS_OK: (None, None),
robot_command_pb2.RobotCommandResponse.STATUS_INVALID_REQUEST: error_pair(InvalidRequestError),
robot_command_pb2.RobotCommandResponse.STATUS_UNSUPPORTED: error_pair(UnsupportedError),
robot_command_pb2.RobotCommandResponse.STATUS_NO_TIMESYNC: error_pair(NoTimeSyncError),
robot_command_pb2.RobotCommandResponse.STATUS_EXPIRED: error_pair(ExpiredError),
robot_command_pb2.RobotCommandResponse.STATUS_TOO_DISTANT: error_pair(TooDistantError),
robot_command_pb2.RobotCommandResponse.STATUS_NOT_POWERED_ON: error_pair(NotPoweredOnError),
robot_command_pb2.RobotCommandResponse.STATUS_BEHAVIOR_FAULT: error_pair(BehaviorFaultError),
robot_command_pb2.RobotCommandResponse.STATUS_DOCKED: error_pair(DockedError),
robot_command_pb2.RobotCommandResponse.STATUS_UNKNOWN_FRAME: error_pair(UnknownFrameError),
})
# yapf: enable
@handle_common_header_errors
@handle_lease_use_result_errors
@handle_unset_status_error(unset='STATUS_UNKNOWN')
def _robot_command_error(response):
"""Return a custom exception based on response, None if no error.
Args:
response: Response message to get the status from.
Returns:
None if status_to_error[status] maps to (None, _).
Otherwise, an instance of an error determined by status_to_error.
"""
return error_factory(response, response.status,
status_to_string=robot_command_pb2.RobotCommandResponse.Status.Name,
status_to_error=_ROBOT_COMMAND_STATUS_TO_ERROR)
@handle_common_header_errors
def _robot_command_feedback_error(response):
# Write custom handling unset errors here. Only one of these statuses needs to be set.
field = 'status'
if ((getattr(response.feedback.full_body_feedback, field)) or
(getattr(response.feedback.synchronized_feedback.mobility_command_feedback, field)) or
(getattr(response.feedback.synchronized_feedback.arm_command_feedback, field)) or
(getattr(response.feedback.synchronized_feedback.gripper_command_feedback, field))):
return None
else:
return UnsetStatusError(response)
def _clear_behavior_fault_value(response):
"""Check if ClearBehaviorFault message status is STATUS_CLEARED.
Args:
response: Response message to check.
Returns:
Boolean whether status in response message is STATUS_CLEARED.
"""
return response.status == robot_command_pb2.ClearBehaviorFaultResponse.STATUS_CLEARED
# yapf: disable
_CLEAR_BEHAVIOR_FAULT_STATUS_TO_ERROR = collections.defaultdict(
lambda: (ResponseError, None))
_CLEAR_BEHAVIOR_FAULT_STATUS_TO_ERROR.update({
robot_command_pb2.ClearBehaviorFaultResponse.STATUS_CLEARED: (None, None),
robot_command_pb2.ClearBehaviorFaultResponse.STATUS_NOT_CLEARED:
(NotClearedError, NotClearedError.__doc__),
})
# yapf: enable
@handle_common_header_errors
@handle_lease_use_result_errors
@handle_unset_status_error(unset='STATUS_UNKNOWN')
def _clear_behavior_fault_error(response):
"""Return a custom exception based on response, None if no error.
Args:
response: Response message to check.
Returns:
custom exception based on response, None if no error
"""
return error_factory(response, response.status,
status_to_string=robot_command_pb2.ClearBehaviorFaultResponse.Status.Name,
status_to_error=_CLEAR_BEHAVIOR_FAULT_STATUS_TO_ERROR)
class RobotCommandBuilder(object):
"""This class contains a set of static helper functions to build and issue robot commands.
This is not intended to cover every use case, but rather give developers a starting point for
issuing commands to the robot.The robot command proto uses several advanced protobuf techniques,
including the use of Any and OneOf.
A RobotCommand is composed of one or more commands. The set of valid commands is robot /
hardware specific. An armless spot only accepts one command at a time. Each command may or may
not take a generic param object. These params are also robot / hardware dependent.
"""
######################
# Full body commands #
######################
@staticmethod
def stop_command():
"""Command to stop with minimal motion. If the robot is walking, it will transition to
stand. If the robot is standing or sitting, it will do nothing.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
full_body_command = full_body_command_pb2.FullBodyCommand.Request(
stop_request=basic_command_pb2.StopCommand.Request())
command = robot_command_pb2.RobotCommand(full_body_command=full_body_command)
return command
@staticmethod
def freeze_command():
"""Command to freeze all joints at their current positions (no balancing control)
Returns:
RobotCommand, which can be issued to the robot command service.
"""
full_body_command = full_body_command_pb2.FullBodyCommand.Request(
freeze_request=basic_command_pb2.FreezeCommand.Request())
command = robot_command_pb2.RobotCommand(full_body_command=full_body_command)
return command
@staticmethod
def selfright_command():
"""Command to get the robot in a ready, sitting position. If the robot is on its back, it
will attempt to flip over.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
full_body_command = full_body_command_pb2.FullBodyCommand.Request(
selfright_request=basic_command_pb2.SelfRightCommand.Request())
command = robot_command_pb2.RobotCommand(full_body_command=full_body_command)
return command
@staticmethod
def battery_change_pose_command(dir_hint=1):
"""Command that will have the robot sit down (if not already sitting) and roll onto its side
for easier battery access.
Args:
dir_hint: Direction to roll over: 1-right/2-left
Returns:
RobotCommand, which can be issued to the robot command service.
"""
command = robot_command_pb2.RobotCommand()
command.full_body_command.battery_change_pose_request.direction_hint = dir_hint
return command
@staticmethod
def payload_estimation_command():
"""Command to get the robot estimate payload mass.
Commands robot to stand and execute a routine to estimate the mass properties of an
unregistered payload attached to the robot.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
full_body_command = full_body_command_pb2.FullBodyCommand.Request(
payload_estimation_request=payload_estimation_pb2.PayloadEstimationCommand.Request())
command = robot_command_pb2.RobotCommand(full_body_command=full_body_command)
return command
@staticmethod
def safe_power_off_command():
"""Command to get robot into a position where it is safe to power down, then power down. If
the robot has fallen, it will power down directly. If the robot is not in a safe position,
it will get to a safe position before powering down. The robot will not power down until it
is in a safe state.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
full_body_command = full_body_command_pb2.FullBodyCommand.Request(
safe_power_off_request=basic_command_pb2.SafePowerOffCommand.Request())
command = robot_command_pb2.RobotCommand(full_body_command=full_body_command)
return command
@staticmethod
def constrained_manipulation_command(
task_type, init_wrench_direction_in_frame_name, force_limit, torque_limit, frame_name,
tangential_speed=None, rotational_speed=None, target_linear_position=None,
target_angle=None,
control_mode=basic_command_pb2.ConstrainedManipulationCommand.Request.CONTROL_MODE_VELOCITY,
reset_estimator=wrappers_pb2.BoolValue(value=True)):
"""Command constrained manipulation. """
if (tangential_speed is None and rotational_speed is None):
raise Exception("Need either translational or rotational speed")
if (target_angle and target_linear_position):
raise Exception("Both target_angle and target_linear_position were specified.")
in_position_control = control_mode == basic_command_pb2.ConstrainedManipulationCommand.Request.CONTROL_MODE_POSITION
if (in_position_control and not (target_angle or target_linear_position)):
raise Exception(
"We are in position control mode, but neither target angle nor position were specified."
)
full_body_command = full_body_command_pb2.FullBodyCommand.Request(
constrained_manipulation_request=basic_command_pb2.ConstrainedManipulationCommand.
Request(task_type=task_type,
init_wrench_direction_in_frame_name=init_wrench_direction_in_frame_name,
frame_name=frame_name, tangential_speed=tangential_speed,
rotational_speed=rotational_speed, target_angle=target_angle,
target_linear_position=target_linear_position, control_mode=control_mode,
reset_estimator=reset_estimator))
full_body_command.constrained_manipulation_request.force_limit.value = force_limit
full_body_command.constrained_manipulation_request.torque_limit.value = torque_limit
command = robot_command_pb2.RobotCommand(full_body_command=full_body_command)
return command
@staticmethod
def joint_command():
command = robot_command_pb2.RobotCommand()
command.full_body_command.joint_request.SetInParent()
return command
#########################
# Synchronized commands #
#########################
@staticmethod
def synchro_se2_trajectory_point_command(goal_x, goal_y, goal_heading, frame_name, params=None,
body_height=0.0,
locomotion_hint=spot_command_pb2.HINT_AUTO,
build_on_command=None):
"""
Command robot to move to pose along a 2D plane. Pose can be specified in the world
(kinematic odometry) frame or the robot body frame. The arguments body_height and
locomotion_hint are ignored if params argument is passed.
A trajectory command requires an end time. End time is not set in this function, but rather
is set externally before call to RobotCommandService.
Args:
goal_x: Position X coordinate.
goal_y: Position Y coordinate.
goal_heading: Pose heading in radians.
frame_name: Name of the frame to use.
params(spot.MobilityParams): Spot specific parameters for mobility commands. If not set,
this will be constructed using other args.
body_height: Height, meters, relative to a nominal stand height.
locomotion_hint: Locomotion hint to use for the trajectory command.
build_on_command: Option to input a RobotCommand (not containing a full_body_command). An
arm_command and gripper_command from this incoming RobotCommand will be added
to the returned RobotCommand.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
position = geometry_pb2.Vec2(x=goal_x, y=goal_y)
pose = geometry_pb2.SE2Pose(position=position, angle=goal_heading)
return RobotCommandBuilder.synchro_se2_trajectory_command(pose, frame_name, params,
body_height, locomotion_hint,
build_on_command)
@staticmethod
def synchro_se2_trajectory_command(goal_se2, frame_name, params=None, body_height=0.0,
locomotion_hint=spot_command_pb2.HINT_AUTO,
build_on_command=None):
"""Command robot to move to pose along a 2D plane. Pose can be specified in the world
(kinematic odometry or vision world) frames. The arguments body_height and
locomotion_hint are ignored if params argument is passed.
A trajectory command requires an end time. End time is not set in this function, but rather
is set externally before call to RobotCommandService.
Args:
goal_se2: SE2Pose goal.
frame_name: Name of the frame to use.
params(spot.MobilityParams): Spot specific parameters for mobility commands. If not set,
this will be constructed using other args.
body_height: Height, meters, relative to a nominal stand height.
locomotion_hint: Locomotion hint to use for the trajectory command.
build_on_command: Option to input a RobotCommand (not containing a full_body_command). An
arm_command and gripper_command from this incoming RobotCommand will be added
to the returned RobotCommand.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
if not params:
params = RobotCommandBuilder.mobility_params(body_height=body_height,
locomotion_hint=locomotion_hint)
any_params = RobotCommandBuilder._to_any(params)
point = trajectory_pb2.SE2TrajectoryPoint(pose=goal_se2)
traj = trajectory_pb2.SE2Trajectory(points=[point])
traj_command = basic_command_pb2.SE2TrajectoryCommand.Request(trajectory=traj,
se2_frame_name=frame_name)
mobility_command = mobility_command_pb2.MobilityCommand.Request(
se2_trajectory_request=traj_command, params=any_params)
synchronized_command = synchronized_command_pb2.SynchronizedCommand.Request(
mobility_command=mobility_command)
robot_command = robot_command_pb2.RobotCommand(synchronized_command=synchronized_command)
if build_on_command:
return RobotCommandBuilder.build_synchro_command(build_on_command, robot_command)
return robot_command
@staticmethod
def synchro_trajectory_command_in_body_frame(
goal_x_rt_body, goal_y_rt_body, goal_heading_rt_body, frame_tree_snapshot, params=None,
body_height=0.0, locomotion_hint=spot_command_pb2.HINT_AUTO, build_on_command=None):
"""Command robot to move to pose described relative to the robots body along a 2D plane. For example,
a command to move forward 2 meters at the same heading will have goal_x_rt_body=2.0, goal_y_rt_body=0.0,
goal_heading_rt_body=0.0.
The arguments body_height and locomotion_hint are ignored if params argument is passed. A trajectory
command requires an end time. End time is not set in this function, but rather is set externally before
call to RobotCommandService.
Args:
goal_x_rt_body: Position X coordinate described relative to the body frame.
goal_y_rt_body: Position Y coordinate described relative to the body frame.
goal_heading_rt_body: Pose heading in radians described relative to the body frame.
frame_tree_snapshot: Dictionary representing the child_to_parent_edge_map describing different
transforms. This can be acquired using the robot state client directly, or using
the robot object's helper function robot.get_frame_tree_snapshot().
params(spot.MobilityParams): Spot specific parameters for mobility commands. If not set,
this will be constructed using other args.
body_height: Height, meters, relative to a nominal stand height.
locomotion_hint: Locomotion hint to use for the trajectory command.
Returns:
RobotCommand, which can be issued to the robot command service. The go-to point will be converted to a
non-moving world frame (odom frame) to be issued to the robot.
"""
goto_rt_body = SE2Pose(goal_x_rt_body, goal_y_rt_body, goal_heading_rt_body)
# Get an SE2 pose for odom_tform_body to convert the body-based command to a non-moving frame
# that can be issued to the robot.
odom_tform_body = get_se2_a_tform_b(frame_tree_snapshot, ODOM_FRAME_NAME, BODY_FRAME_NAME)
odom_tform_goto = odom_tform_body * goto_rt_body
return RobotCommandBuilder.synchro_se2_trajectory_command(odom_tform_goto.to_proto(),
ODOM_FRAME_NAME, params,
body_height, locomotion_hint,
build_on_command=build_on_command)
@staticmethod
def synchro_velocity_command(v_x, v_y, v_rot, params=None, body_height=0.0,
locomotion_hint=spot_command_pb2.HINT_AUTO,
frame_name=BODY_FRAME_NAME, build_on_command=None):
"""Command robot to move along 2D plane. Velocity should be specified in the robot body
frame. Other frames are currently not supported. The arguments body_height and
locomotion_hint are ignored if params argument is passed.
A velocity command requires an end time. End time is not set in this function, but rather
is set externally before call to RobotCommandService.
Args:
v_x: Velocity in X direction.
v_y: Velocity in Y direction.
v_rot: Velocity heading in radians.
params(spot.MobilityParams): Spot specific parameters for mobility commands. If not set,
this will be constructed using other args.
body_height: Height, meters, relative to a nominal stand height.
locomotion_hint: Locomotion hint to use for the velocity command.
frame_name: Name of the frame to use.
build_on_command: Option to input a RobotCommand (not containing a full_body_command). An
arm_command and gripper_command from this incoming RobotCommand will be added
to the returned RobotCommand.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
if not params:
params = RobotCommandBuilder.mobility_params(body_height=body_height,
locomotion_hint=locomotion_hint)
any_params = RobotCommandBuilder._to_any(params)
linear = geometry_pb2.Vec2(x=v_x, y=v_y)
vel = geometry_pb2.SE2Velocity(linear=linear, angular=v_rot)
slew_rate_limit = geometry_pb2.SE2Velocity(linear=geometry_pb2.Vec2(x=4, y=4), angular=2.0)
vel_command = basic_command_pb2.SE2VelocityCommand.Request(velocity=vel,
se2_frame_name=frame_name,
slew_rate_limit=slew_rate_limit)
mobility_command = mobility_command_pb2.MobilityCommand.Request(
se2_velocity_request=vel_command, params=any_params)
synchronized_command = synchronized_command_pb2.SynchronizedCommand.Request(
mobility_command=mobility_command)
robot_command = robot_command_pb2.RobotCommand(synchronized_command=synchronized_command)
if build_on_command:
return RobotCommandBuilder.build_synchro_command(build_on_command, robot_command)
return robot_command
@staticmethod
def synchro_stand_command(params=None, body_height=0.0, footprint_R_body=geometry.EulerZXY(),
build_on_command=None):
"""Command robot to stand. If the robot is sitting, it will stand up. If the robot is
moving, it will come to a stop. Params can specify a trajectory for the body to follow
while standing. In the simplest case, this can be a specific position+orientation which the
body will hold at. The arguments body_height and footprint_R_body are ignored if params
argument is passed.
Args:
params(spot.MobilityParams): Spot specific parameters for mobility commands. If not set,
this will be constructed using other args.
body_height(float): Height, meters, to stand at relative to a nominal stand height.
footprint_R_body(EulerZXY): The orientation of the body frame with respect to the
footprint frame (gravity aligned framed with yaw computed from the stance feet)
build_on_command: Option to input a RobotCommand (not containing a full_body_command). An
arm_command and gripper_command from this incoming RobotCommand will be added
to the returned RobotCommand.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
if not params:
params = RobotCommandBuilder.mobility_params(body_height=body_height,
footprint_R_body=footprint_R_body)
any_params = RobotCommandBuilder._to_any(params)
mobility_command = mobility_command_pb2.MobilityCommand.Request(
stand_request=basic_command_pb2.StandCommand.Request(), params=any_params)
synchronized_command = synchronized_command_pb2.SynchronizedCommand.Request(
mobility_command=mobility_command)
robot_command = robot_command_pb2.RobotCommand(synchronized_command=synchronized_command)
if build_on_command:
return RobotCommandBuilder.build_synchro_command(build_on_command, robot_command)
return robot_command
@staticmethod
def synchro_sit_command(params=None, build_on_command=None):
"""Command the robot to sit.
Args:
params(spot.MobilityParams): Spot specific parameters for mobility commands.
build_on_command: Option to input a RobotCommand (not containing a full_body_command). An
arm_command and gripper_command from this incoming RobotCommand will be added
to the returned RobotCommand.
Returns:
RobotCommand, which can be issued to the robot command service.
"""
if not params:
params = RobotCommandBuilder.mobility_params()
any_params = RobotCommandBuilder._to_any(params)
mobility_command = mobility_command_pb2.MobilityCommand.Request(
sit_request=basic_command_pb2.SitCommand.Request(), params=any_params)
synchronized_command = synchronized_command_pb2.SynchronizedCommand.Request(
mobility_command=mobility_command)
robot_command = robot_command_pb2.RobotCommand(synchronized_command=synchronized_command)