dexcontrol 0.2.1__py3-none-any.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.

Potentially problematic release.


This version of dexcontrol might be problematic. Click here for more details.

Files changed (72) hide show
  1. dexcontrol/__init__.py +45 -0
  2. dexcontrol/apps/dualsense_teleop_base.py +371 -0
  3. dexcontrol/config/__init__.py +14 -0
  4. dexcontrol/config/core/__init__.py +22 -0
  5. dexcontrol/config/core/arm.py +32 -0
  6. dexcontrol/config/core/chassis.py +22 -0
  7. dexcontrol/config/core/hand.py +42 -0
  8. dexcontrol/config/core/head.py +33 -0
  9. dexcontrol/config/core/misc.py +37 -0
  10. dexcontrol/config/core/torso.py +36 -0
  11. dexcontrol/config/sensors/__init__.py +4 -0
  12. dexcontrol/config/sensors/cameras/__init__.py +7 -0
  13. dexcontrol/config/sensors/cameras/gemini_camera.py +16 -0
  14. dexcontrol/config/sensors/cameras/rgb_camera.py +15 -0
  15. dexcontrol/config/sensors/imu/__init__.py +6 -0
  16. dexcontrol/config/sensors/imu/gemini_imu.py +15 -0
  17. dexcontrol/config/sensors/imu/nine_axis_imu.py +15 -0
  18. dexcontrol/config/sensors/lidar/__init__.py +6 -0
  19. dexcontrol/config/sensors/lidar/rplidar.py +15 -0
  20. dexcontrol/config/sensors/ultrasonic/__init__.py +6 -0
  21. dexcontrol/config/sensors/ultrasonic/ultrasonic.py +15 -0
  22. dexcontrol/config/sensors/vega_sensors.py +65 -0
  23. dexcontrol/config/vega.py +203 -0
  24. dexcontrol/core/__init__.py +0 -0
  25. dexcontrol/core/arm.py +324 -0
  26. dexcontrol/core/chassis.py +628 -0
  27. dexcontrol/core/component.py +834 -0
  28. dexcontrol/core/hand.py +170 -0
  29. dexcontrol/core/head.py +232 -0
  30. dexcontrol/core/misc.py +514 -0
  31. dexcontrol/core/torso.py +198 -0
  32. dexcontrol/proto/dexcontrol_msg_pb2.py +69 -0
  33. dexcontrol/proto/dexcontrol_msg_pb2.pyi +168 -0
  34. dexcontrol/proto/dexcontrol_query_pb2.py +73 -0
  35. dexcontrol/proto/dexcontrol_query_pb2.pyi +134 -0
  36. dexcontrol/robot.py +1091 -0
  37. dexcontrol/sensors/__init__.py +40 -0
  38. dexcontrol/sensors/camera/__init__.py +18 -0
  39. dexcontrol/sensors/camera/gemini_camera.py +139 -0
  40. dexcontrol/sensors/camera/rgb_camera.py +98 -0
  41. dexcontrol/sensors/imu/__init__.py +22 -0
  42. dexcontrol/sensors/imu/gemini_imu.py +139 -0
  43. dexcontrol/sensors/imu/nine_axis_imu.py +149 -0
  44. dexcontrol/sensors/lidar/__init__.py +3 -0
  45. dexcontrol/sensors/lidar/rplidar.py +164 -0
  46. dexcontrol/sensors/manager.py +185 -0
  47. dexcontrol/sensors/ultrasonic.py +110 -0
  48. dexcontrol/utils/__init__.py +15 -0
  49. dexcontrol/utils/constants.py +12 -0
  50. dexcontrol/utils/io_utils.py +26 -0
  51. dexcontrol/utils/motion_utils.py +194 -0
  52. dexcontrol/utils/os_utils.py +39 -0
  53. dexcontrol/utils/pb_utils.py +103 -0
  54. dexcontrol/utils/rate_limiter.py +167 -0
  55. dexcontrol/utils/reset_orbbec_camera_usb.py +98 -0
  56. dexcontrol/utils/subscribers/__init__.py +44 -0
  57. dexcontrol/utils/subscribers/base.py +260 -0
  58. dexcontrol/utils/subscribers/camera.py +328 -0
  59. dexcontrol/utils/subscribers/decoders.py +83 -0
  60. dexcontrol/utils/subscribers/generic.py +105 -0
  61. dexcontrol/utils/subscribers/imu.py +170 -0
  62. dexcontrol/utils/subscribers/lidar.py +195 -0
  63. dexcontrol/utils/subscribers/protobuf.py +106 -0
  64. dexcontrol/utils/timer.py +136 -0
  65. dexcontrol/utils/trajectory_utils.py +40 -0
  66. dexcontrol/utils/viz_utils.py +86 -0
  67. dexcontrol-0.2.1.dist-info/METADATA +369 -0
  68. dexcontrol-0.2.1.dist-info/RECORD +72 -0
  69. dexcontrol-0.2.1.dist-info/WHEEL +5 -0
  70. dexcontrol-0.2.1.dist-info/licenses/LICENSE +188 -0
  71. dexcontrol-0.2.1.dist-info/licenses/NOTICE +13 -0
  72. dexcontrol-0.2.1.dist-info/top_level.txt +1 -0
@@ -0,0 +1,198 @@
1
+ # Copyright (c) 2025 Dexmate CORPORATION & AFFILIATES. All rights reserved.
2
+ #
3
+ # Licensed under the Apache License, Version 2.0 with Commons Clause License
4
+ # Condition v1.0 [see LICENSE for details].
5
+
6
+ """Robot torso control module.
7
+
8
+ This module provides the Torso class for controlling a robot torso through Zenoh
9
+ communication. It handles joint position and velocity control and state monitoring.
10
+ """
11
+
12
+ import time
13
+
14
+ import numpy as np
15
+ import zenoh
16
+ from jaxtyping import Float
17
+
18
+ from dexcontrol.config.core import TorsoConfig
19
+ from dexcontrol.core.component import RobotJointComponent
20
+ from dexcontrol.proto import dexcontrol_msg_pb2
21
+
22
+
23
+ class Torso(RobotJointComponent):
24
+ """Robot torso control class.
25
+
26
+ This class provides methods to control a robot torso by publishing commands and
27
+ receiving state information through Zenoh communication.
28
+
29
+ Attributes:
30
+ default_vel: Default joint velocity in rad/s when not explicitly specified.
31
+ max_vel: Maximum allowed joint velocity in rad/s.
32
+ """
33
+
34
+ def __init__(
35
+ self,
36
+ configs: TorsoConfig,
37
+ zenoh_session: zenoh.Session,
38
+ ) -> None:
39
+ """Initialize the torso controller.
40
+
41
+ Args:
42
+ configs: Torso configuration parameters containing communication topics
43
+ and default velocity settings.
44
+ zenoh_session: Active Zenoh communication session for message passing.
45
+ """
46
+ super().__init__(
47
+ state_sub_topic=configs.state_sub_topic,
48
+ control_pub_topic=configs.control_pub_topic,
49
+ state_message_type=dexcontrol_msg_pb2.TorsoState,
50
+ zenoh_session=zenoh_session,
51
+ joint_name=configs.joint_name,
52
+ pose_pool=configs.pose_pool,
53
+ )
54
+ self.default_vel = configs.default_vel
55
+ self.max_vel = configs.max_vel
56
+
57
+ def set_joint_pos_vel(
58
+ self,
59
+ joint_pos: Float[np.ndarray, "3"] | list[float] | dict[str, float],
60
+ joint_vel: Float[np.ndarray, "3"]
61
+ | list[float]
62
+ | dict[str, float]
63
+ | float
64
+ | None = None,
65
+ relative: bool = False,
66
+ wait_time: float = 0.0,
67
+ ) -> None:
68
+ """Send control commands to the torso.
69
+
70
+ Args:
71
+ joint_pos: Joint positions as either:
72
+ - List of joint values [j1, j2, j3]
73
+ - Numpy array with shape (3,), in radians
74
+ - Dictionary mapping joint names to position values
75
+ joint_vel: Optional joint velocities as either:
76
+ - List of joint values [v1, v2, v3]
77
+ - Numpy array with shape (3,), in rad/s
78
+ - Dictionary mapping joint names to velocity values
79
+ - Single float value to be applied to all joints
80
+ If None, velocities are calculated based on default velocity setting.
81
+ relative: If True, the joint positions are relative to the current position.
82
+ wait_time: Time to wait after sending command in seconds. If 0, returns
83
+ immediately after sending command.
84
+
85
+ Raises:
86
+ ValueError: If wait_time is negative or joint_pos dictionary contains
87
+ invalid joint names.
88
+ """
89
+ if wait_time < 0.0:
90
+ raise ValueError("wait_time must be greater than or equal to 0")
91
+
92
+ # Handle relative positioning
93
+ if relative:
94
+ joint_pos = self._resolve_relative_joint_cmd(joint_pos)
95
+
96
+ # Convert inputs to numpy arrays
97
+ joint_pos = self._convert_joint_cmd_to_array(joint_pos)
98
+ joint_vel = self._process_joint_velocities(joint_vel, joint_pos)
99
+
100
+ # Create and send control message
101
+ control_msg = dexcontrol_msg_pb2.TorsoCommand()
102
+ control_msg.joint_pos.extend(joint_pos.tolist())
103
+ control_msg.joint_vel.extend(joint_vel.tolist())
104
+ self._publish_control(control_msg)
105
+
106
+ # Wait if specified
107
+ if wait_time > 0.0:
108
+ time.sleep(wait_time)
109
+
110
+ def set_joint_pos(
111
+ self,
112
+ joint_pos: Float[np.ndarray, "3"] | list[float] | dict[str, float],
113
+ relative: bool = False,
114
+ wait_time: float = 0.0,
115
+ wait_kwargs: dict[str, float] | None = None,
116
+ ) -> None:
117
+ """Send joint position control commands to the torso.
118
+
119
+ Args:
120
+ joint_pos: Joint positions as either:
121
+ - List of joint values [j1, j2, j3]
122
+ - Numpy array with shape (3,), in radians
123
+ - Dictionary mapping joint names to position values
124
+ relative: If True, the joint positions are relative to the current position.
125
+ wait_time: Time to wait after sending command in seconds. If 0, returns
126
+ immediately after sending command.
127
+ wait_kwargs: Optional parameters for trajectory generation (not used in Torso).
128
+
129
+ Raises:
130
+ ValueError: If joint_pos dictionary contains invalid joint names.
131
+ """
132
+ self.set_joint_pos_vel(
133
+ joint_pos, joint_vel=None, relative=relative, wait_time=wait_time
134
+ )
135
+
136
+ def stop(self) -> None:
137
+ """Stop the torso by setting target position to current position with zero velocity."""
138
+ current_pos = self.get_joint_pos()
139
+ zero_vel = np.zeros(3, dtype=np.float32)
140
+ self.set_joint_pos_vel(current_pos, zero_vel, relative=False, wait_time=0.0)
141
+
142
+ @property
143
+ def pitch_angle(self) -> float:
144
+ """Gets the pitch angle of the torso.
145
+
146
+ The pitch angle is defined as the angle between the third link (the link that
147
+ is closest to the arms) and the horizontal plane.
148
+
149
+ Examples:
150
+ At zero position: shoulder pitch angle = pi/2
151
+ At (60, 120, -30) degrees: shoulder pitch angle = 0
152
+
153
+ Returns:
154
+ The pitch angle in radians.
155
+ """
156
+ joint_pos = self.get_joint_pos()
157
+ return joint_pos[0] + joint_pos[2] + np.pi / 2 - joint_pos[1]
158
+
159
+ def shutdown(self) -> None:
160
+ """Clean up Zenoh resources for the torso component."""
161
+ self.stop()
162
+ super().shutdown()
163
+
164
+ def _process_joint_velocities(
165
+ self,
166
+ joint_vel: Float[np.ndarray, "3"]
167
+ | list[float]
168
+ | dict[str, float]
169
+ | float
170
+ | None,
171
+ joint_pos: np.ndarray,
172
+ ) -> np.ndarray:
173
+ """Process and validate joint velocities.
174
+
175
+ Args:
176
+ joint_vel: Joint velocities in various formats or None.
177
+ joint_pos: Target joint positions for velocity calculation.
178
+
179
+ Returns:
180
+ Processed joint velocities as numpy array.
181
+ """
182
+ if joint_vel is None:
183
+ # Calculate velocities based on motion direction and default velocity
184
+ joint_motion = np.abs(joint_pos - self.get_joint_pos())
185
+ motion_norm = np.linalg.norm(joint_motion)
186
+
187
+ if motion_norm < 1e-6: # Avoid division by zero
188
+ return np.zeros(3, dtype=np.float32)
189
+
190
+ # Scale velocities by default velocity
191
+ return (joint_motion / motion_norm) * self.default_vel
192
+
193
+ if isinstance(joint_vel, (int, float)):
194
+ # Single value - apply to all joints
195
+ return np.full(3, joint_vel, dtype=np.float32)
196
+
197
+ # Convert to array and clip to max velocity
198
+ return self._convert_joint_cmd_to_array(joint_vel, clip_value=self.max_vel)
@@ -0,0 +1,69 @@
1
+ # -*- coding: utf-8 -*-
2
+ # Generated by the protocol buffer compiler. DO NOT EDIT!
3
+ # NO CHECKED-IN PROTOBUF GENCODE
4
+ # source: dexcontrol_msg.proto
5
+ # Protobuf Python Version: 6.31.0
6
+ """Generated protocol buffer code."""
7
+ from google.protobuf import descriptor as _descriptor
8
+ from google.protobuf import descriptor_pool as _descriptor_pool
9
+ from google.protobuf import runtime_version as _runtime_version
10
+ from google.protobuf import symbol_database as _symbol_database
11
+ from google.protobuf.internal import builder as _builder
12
+
13
+ _runtime_version.ValidateProtobufRuntimeVersion(
14
+ _runtime_version.Domain.PUBLIC,
15
+ 6,
16
+ 31,
17
+ 0,
18
+ '',
19
+ 'dexcontrol_msg.proto'
20
+ )
21
+ # @@protoc_insertion_point(imports)
22
+
23
+ _sym_db = _symbol_database.Default()
24
+
25
+
26
+
27
+
28
+ DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x14\x64\x65xcontrol_msg.proto\x12\ndexcontrol\"V\n\x08\x41rmState\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\x12\x11\n\tjoint_vel\x18\x02 \x03(\x02\x12\x11\n\tjoint_cur\x18\x03 \x03(\x02\x12\x11\n\tjoint_err\x18\x04 \x03(\r\"F\n\tHandState\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\x12\x11\n\tjoint_vel\x18\x02 \x03(\x02\x12\x13\n\x0bjoint_statu\x18\x03 \x03(\r\"1\n\tHeadState\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\x12\x11\n\tjoint_vel\x18\x02 \x03(\x02\"2\n\nTorsoState\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\x12\x11\n\tjoint_vel\x18\x02 \x03(\x02\"a\n\x10SingleWheelState\x12\x14\n\x0csteering_pos\x18\x01 \x01(\x02\x12\x11\n\twheel_pos\x18\x02 \x01(\x02\x12\x11\n\twheel_vel\x18\x03 \x01(\x02\x12\x11\n\twheel_cur\x18\x04 \x01(\x02\"g\n\x0c\x43hassisState\x12*\n\x04left\x18\x01 \x01(\x0b\x32\x1c.dexcontrol.SingleWheelState\x12+\n\x05right\x18\x02 \x01(\x0b\x32\x1c.dexcontrol.SingleWheelState\"j\n\x08\x42MSState\x12\x0f\n\x07voltage\x18\x01 \x01(\x02\x12\x0f\n\x07\x63urrent\x18\x02 \x01(\x02\x12\x13\n\x0btemperature\x18\x03 \x01(\x02\x12\x12\n\npercentage\x18\x04 \x01(\r\x12\x13\n\x0bis_charging\x18\x05 \x01(\x08\"H\n\x0bWrenchState\x12\x0e\n\x06wrench\x18\x01 \x03(\x02\x12\x13\n\x0b\x62lue_button\x18\x02 \x01(\x08\x12\x14\n\x0cgreen_button\x18\x03 \x01(\x08\"D\n\nEStopState\x12\x16\n\x0e\x62utton_pressed\x18\x01 \x01(\x08\x12\x1e\n\x16software_estop_enabled\x18\x02 \x01(\x08\"a\n\x0fUltrasonicState\x12\x12\n\nfront_left\x18\x01 \x01(\x02\x12\x13\n\x0b\x66ront_right\x18\x02 \x01(\x02\x12\x11\n\tback_left\x18\x03 \x01(\x02\x12\x12\n\nback_right\x18\x04 \x01(\x02\"\xa3\x01\n\nArmCommand\x12\x38\n\x0c\x63ommand_type\x18\x01 \x01(\x0e\x32\".dexcontrol.ArmCommand.CommandType\x12\x11\n\tjoint_pos\x18\x02 \x03(\x02\x12\x11\n\tjoint_vel\x18\x03 \x03(\x02\"5\n\x0b\x43ommandType\x12\x0c\n\x08POSITION\x10\x00\x12\x18\n\x14VELOCITY_FEEDFORWARD\x10\x01\" \n\x0bHandCommand\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\"3\n\x0bHeadCommand\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\x12\x11\n\tjoint_vel\x18\x02 \x03(\x02\"4\n\x0cTorsoCommand\x12\x11\n\tjoint_pos\x18\x01 \x03(\x02\x12\x11\n\tjoint_vel\x18\x02 \x03(\x02\"=\n\x12SingleWheelCommand\x12\x14\n\x0csteering_pos\x18\x01 \x01(\x02\x12\x11\n\twheel_vel\x18\x02 \x01(\x02\"m\n\x0e\x43hassisCommand\x12,\n\x04left\x18\x01 \x01(\x0b\x32\x1e.dexcontrol.SingleWheelCommand\x12-\n\x05right\x18\x02 \x01(\x0b\x32\x1e.dexcontrol.SingleWheelCommandb\x06proto3')
29
+
30
+ _globals = globals()
31
+ _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals)
32
+ _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'dexcontrol_msg_pb2', _globals)
33
+ if not _descriptor._USE_C_DESCRIPTORS:
34
+ DESCRIPTOR._loaded_options = None
35
+ _globals['_ARMSTATE']._serialized_start=36
36
+ _globals['_ARMSTATE']._serialized_end=122
37
+ _globals['_HANDSTATE']._serialized_start=124
38
+ _globals['_HANDSTATE']._serialized_end=194
39
+ _globals['_HEADSTATE']._serialized_start=196
40
+ _globals['_HEADSTATE']._serialized_end=245
41
+ _globals['_TORSOSTATE']._serialized_start=247
42
+ _globals['_TORSOSTATE']._serialized_end=297
43
+ _globals['_SINGLEWHEELSTATE']._serialized_start=299
44
+ _globals['_SINGLEWHEELSTATE']._serialized_end=396
45
+ _globals['_CHASSISSTATE']._serialized_start=398
46
+ _globals['_CHASSISSTATE']._serialized_end=501
47
+ _globals['_BMSSTATE']._serialized_start=503
48
+ _globals['_BMSSTATE']._serialized_end=609
49
+ _globals['_WRENCHSTATE']._serialized_start=611
50
+ _globals['_WRENCHSTATE']._serialized_end=683
51
+ _globals['_ESTOPSTATE']._serialized_start=685
52
+ _globals['_ESTOPSTATE']._serialized_end=753
53
+ _globals['_ULTRASONICSTATE']._serialized_start=755
54
+ _globals['_ULTRASONICSTATE']._serialized_end=852
55
+ _globals['_ARMCOMMAND']._serialized_start=855
56
+ _globals['_ARMCOMMAND']._serialized_end=1018
57
+ _globals['_ARMCOMMAND_COMMANDTYPE']._serialized_start=965
58
+ _globals['_ARMCOMMAND_COMMANDTYPE']._serialized_end=1018
59
+ _globals['_HANDCOMMAND']._serialized_start=1020
60
+ _globals['_HANDCOMMAND']._serialized_end=1052
61
+ _globals['_HEADCOMMAND']._serialized_start=1054
62
+ _globals['_HEADCOMMAND']._serialized_end=1105
63
+ _globals['_TORSOCOMMAND']._serialized_start=1107
64
+ _globals['_TORSOCOMMAND']._serialized_end=1159
65
+ _globals['_SINGLEWHEELCOMMAND']._serialized_start=1161
66
+ _globals['_SINGLEWHEELCOMMAND']._serialized_end=1222
67
+ _globals['_CHASSISCOMMAND']._serialized_start=1224
68
+ _globals['_CHASSISCOMMAND']._serialized_end=1333
69
+ # @@protoc_insertion_point(module_scope)
@@ -0,0 +1,168 @@
1
+ from collections.abc import Iterable as _Iterable
2
+ from collections.abc import Mapping as _Mapping
3
+ from typing import ClassVar as _ClassVar
4
+ from typing import Optional as _Optional
5
+ from typing import Union as _Union
6
+
7
+ from google.protobuf import descriptor as _descriptor
8
+ from google.protobuf import message as _message
9
+ from google.protobuf.internal import containers as _containers
10
+ from google.protobuf.internal import enum_type_wrapper as _enum_type_wrapper
11
+
12
+ DESCRIPTOR: _descriptor.FileDescriptor
13
+
14
+ class ArmState(_message.Message):
15
+ __slots__ = ("joint_pos", "joint_vel", "joint_cur", "joint_err")
16
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
17
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
18
+ JOINT_CUR_FIELD_NUMBER: _ClassVar[int]
19
+ JOINT_ERR_FIELD_NUMBER: _ClassVar[int]
20
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
21
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
22
+ joint_cur: _containers.RepeatedScalarFieldContainer[float]
23
+ joint_err: _containers.RepeatedScalarFieldContainer[int]
24
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ..., joint_cur: _Optional[_Iterable[float]] = ..., joint_err: _Optional[_Iterable[int]] = ...) -> None: ...
25
+
26
+ class HandState(_message.Message):
27
+ __slots__ = ("joint_pos", "joint_vel", "joint_statu")
28
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
29
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
30
+ JOINT_STATU_FIELD_NUMBER: _ClassVar[int]
31
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
32
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
33
+ joint_statu: _containers.RepeatedScalarFieldContainer[int]
34
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ..., joint_statu: _Optional[_Iterable[int]] = ...) -> None: ...
35
+
36
+ class HeadState(_message.Message):
37
+ __slots__ = ("joint_pos", "joint_vel")
38
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
39
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
40
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
41
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
42
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ...) -> None: ...
43
+
44
+ class TorsoState(_message.Message):
45
+ __slots__ = ("joint_pos", "joint_vel")
46
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
47
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
48
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
49
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
50
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ...) -> None: ...
51
+
52
+ class SingleWheelState(_message.Message):
53
+ __slots__ = ("steering_pos", "wheel_pos", "wheel_vel", "wheel_cur")
54
+ STEERING_POS_FIELD_NUMBER: _ClassVar[int]
55
+ WHEEL_POS_FIELD_NUMBER: _ClassVar[int]
56
+ WHEEL_VEL_FIELD_NUMBER: _ClassVar[int]
57
+ WHEEL_CUR_FIELD_NUMBER: _ClassVar[int]
58
+ steering_pos: float
59
+ wheel_pos: float
60
+ wheel_vel: float
61
+ wheel_cur: float
62
+ def __init__(self, steering_pos: _Optional[float] = ..., wheel_pos: _Optional[float] = ..., wheel_vel: _Optional[float] = ..., wheel_cur: _Optional[float] = ...) -> None: ...
63
+
64
+ class ChassisState(_message.Message):
65
+ __slots__ = ("left", "right")
66
+ LEFT_FIELD_NUMBER: _ClassVar[int]
67
+ RIGHT_FIELD_NUMBER: _ClassVar[int]
68
+ left: SingleWheelState
69
+ right: SingleWheelState
70
+ def __init__(self, left: _Optional[_Union[SingleWheelState, _Mapping]] = ..., right: _Optional[_Union[SingleWheelState, _Mapping]] = ...) -> None: ...
71
+
72
+ class BMSState(_message.Message):
73
+ __slots__ = ("voltage", "current", "temperature", "percentage", "is_charging")
74
+ VOLTAGE_FIELD_NUMBER: _ClassVar[int]
75
+ CURRENT_FIELD_NUMBER: _ClassVar[int]
76
+ TEMPERATURE_FIELD_NUMBER: _ClassVar[int]
77
+ PERCENTAGE_FIELD_NUMBER: _ClassVar[int]
78
+ IS_CHARGING_FIELD_NUMBER: _ClassVar[int]
79
+ voltage: float
80
+ current: float
81
+ temperature: float
82
+ percentage: int
83
+ is_charging: bool
84
+ def __init__(self, voltage: _Optional[float] = ..., current: _Optional[float] = ..., temperature: _Optional[float] = ..., percentage: _Optional[int] = ..., is_charging: bool = ...) -> None: ...
85
+
86
+ class WrenchState(_message.Message):
87
+ __slots__ = ("wrench", "blue_button", "green_button")
88
+ WRENCH_FIELD_NUMBER: _ClassVar[int]
89
+ BLUE_BUTTON_FIELD_NUMBER: _ClassVar[int]
90
+ GREEN_BUTTON_FIELD_NUMBER: _ClassVar[int]
91
+ wrench: _containers.RepeatedScalarFieldContainer[float]
92
+ blue_button: bool
93
+ green_button: bool
94
+ def __init__(self, wrench: _Optional[_Iterable[float]] = ..., blue_button: bool = ..., green_button: bool = ...) -> None: ...
95
+
96
+ class EStopState(_message.Message):
97
+ __slots__ = ("button_pressed", "software_estop_enabled")
98
+ BUTTON_PRESSED_FIELD_NUMBER: _ClassVar[int]
99
+ SOFTWARE_ESTOP_ENABLED_FIELD_NUMBER: _ClassVar[int]
100
+ button_pressed: bool
101
+ software_estop_enabled: bool
102
+ def __init__(self, button_pressed: bool = ..., software_estop_enabled: bool = ...) -> None: ...
103
+
104
+ class UltrasonicState(_message.Message):
105
+ __slots__ = ("front_left", "front_right", "back_left", "back_right")
106
+ FRONT_LEFT_FIELD_NUMBER: _ClassVar[int]
107
+ FRONT_RIGHT_FIELD_NUMBER: _ClassVar[int]
108
+ BACK_LEFT_FIELD_NUMBER: _ClassVar[int]
109
+ BACK_RIGHT_FIELD_NUMBER: _ClassVar[int]
110
+ front_left: float
111
+ front_right: float
112
+ back_left: float
113
+ back_right: float
114
+ def __init__(self, front_left: _Optional[float] = ..., front_right: _Optional[float] = ..., back_left: _Optional[float] = ..., back_right: _Optional[float] = ...) -> None: ...
115
+
116
+ class ArmCommand(_message.Message):
117
+ __slots__ = ("command_type", "joint_pos", "joint_vel")
118
+ class CommandType(int, metaclass=_enum_type_wrapper.EnumTypeWrapper):
119
+ __slots__ = ()
120
+ POSITION: _ClassVar[ArmCommand.CommandType]
121
+ VELOCITY_FEEDFORWARD: _ClassVar[ArmCommand.CommandType]
122
+ POSITION: ArmCommand.CommandType
123
+ VELOCITY_FEEDFORWARD: ArmCommand.CommandType
124
+ COMMAND_TYPE_FIELD_NUMBER: _ClassVar[int]
125
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
126
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
127
+ command_type: ArmCommand.CommandType
128
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
129
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
130
+ def __init__(self, command_type: _Optional[_Union[ArmCommand.CommandType, str]] = ..., joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ...) -> None: ...
131
+
132
+ class HandCommand(_message.Message):
133
+ __slots__ = ("joint_pos",)
134
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
135
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
136
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ...) -> None: ...
137
+
138
+ class HeadCommand(_message.Message):
139
+ __slots__ = ("joint_pos", "joint_vel")
140
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
141
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
142
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
143
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
144
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ...) -> None: ...
145
+
146
+ class TorsoCommand(_message.Message):
147
+ __slots__ = ("joint_pos", "joint_vel")
148
+ JOINT_POS_FIELD_NUMBER: _ClassVar[int]
149
+ JOINT_VEL_FIELD_NUMBER: _ClassVar[int]
150
+ joint_pos: _containers.RepeatedScalarFieldContainer[float]
151
+ joint_vel: _containers.RepeatedScalarFieldContainer[float]
152
+ def __init__(self, joint_pos: _Optional[_Iterable[float]] = ..., joint_vel: _Optional[_Iterable[float]] = ...) -> None: ...
153
+
154
+ class SingleWheelCommand(_message.Message):
155
+ __slots__ = ("steering_pos", "wheel_vel")
156
+ STEERING_POS_FIELD_NUMBER: _ClassVar[int]
157
+ WHEEL_VEL_FIELD_NUMBER: _ClassVar[int]
158
+ steering_pos: float
159
+ wheel_vel: float
160
+ def __init__(self, steering_pos: _Optional[float] = ..., wheel_vel: _Optional[float] = ...) -> None: ...
161
+
162
+ class ChassisCommand(_message.Message):
163
+ __slots__ = ("left", "right")
164
+ LEFT_FIELD_NUMBER: _ClassVar[int]
165
+ RIGHT_FIELD_NUMBER: _ClassVar[int]
166
+ left: SingleWheelCommand
167
+ right: SingleWheelCommand
168
+ def __init__(self, left: _Optional[_Union[SingleWheelCommand, _Mapping]] = ..., right: _Optional[_Union[SingleWheelCommand, _Mapping]] = ...) -> None: ...
@@ -0,0 +1,73 @@
1
+ # -*- coding: utf-8 -*-
2
+ # Generated by the protocol buffer compiler. DO NOT EDIT!
3
+ # NO CHECKED-IN PROTOBUF GENCODE
4
+ # source: dexcontrol_query.proto
5
+ # Protobuf Python Version: 6.31.0
6
+ """Generated protocol buffer code."""
7
+ from google.protobuf import descriptor as _descriptor
8
+ from google.protobuf import descriptor_pool as _descriptor_pool
9
+ from google.protobuf import runtime_version as _runtime_version
10
+ from google.protobuf import symbol_database as _symbol_database
11
+ from google.protobuf.internal import builder as _builder
12
+
13
+ _runtime_version.ValidateProtobufRuntimeVersion(
14
+ _runtime_version.Domain.PUBLIC,
15
+ 6,
16
+ 31,
17
+ 0,
18
+ '',
19
+ 'dexcontrol_query.proto'
20
+ )
21
+ # @@protoc_insertion_point(imports)
22
+
23
+ _sym_db = _symbol_database.Default()
24
+
25
+
26
+
27
+
28
+ DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x16\x64\x65xcontrol_query.proto\x12\ndexcontrol\"Z\n\nSetArmMode\x12)\n\x04mode\x18\x01 \x01(\x0e\x32\x1b.dexcontrol.SetArmMode.Mode\"!\n\x04Mode\x12\x0c\n\x08POSITION\x10\x00\x12\x0b\n\x07\x44ISABLE\x10\x01\"Z\n\x0bSetHeadMode\x12*\n\x04mode\x18\x01 \x01(\x0e\x32\x1c.dexcontrol.SetHeadMode.Mode\"\x1f\n\x04Mode\x12\n\n\x06\x45NABLE\x10\x00\x12\x0b\n\x07\x44ISABLE\x10\x01\"\x1a\n\x08SetEstop\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\"\x18\n\x06SetLed\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\"\x82\x01\n\nClearError\x12\x33\n\tcomponent\x18\x01 \x01(\x0e\x32 .dexcontrol.ClearError.Component\"?\n\tComponent\x12\x0c\n\x08LEFT_ARM\x10\x00\x12\r\n\tRIGHT_ARM\x10\x01\x12\x08\n\x04HEAD\x10\x02\x12\x0b\n\x07\x43HASSIS\x10\x03\"y\n\x0fRebootComponent\x12\x38\n\tcomponent\x18\x01 \x01(\x0e\x32%.dexcontrol.RebootComponent.Component\",\n\tComponent\x12\x07\n\x03\x41RM\x10\x00\x12\t\n\x05TORSO\x10\x01\x12\x0b\n\x07\x43HASSIS\x10\x02\"X\n\x0f\x46irmwareVersion\x12\x18\n\x10hardware_version\x18\x01 \x01(\x05\x12\x18\n\x10software_version\x18\x02 \x01(\x05\x12\x11\n\tmain_hash\x18\x03 \x01(\t\"\xb2\x01\n\x0fSoftwareVersion\x12J\n\x10\x66irmware_version\x18\x01 \x03(\x0b\x32\x30.dexcontrol.SoftwareVersion.FirmwareVersionEntry\x1aS\n\x14\x46irmwareVersionEntry\x12\x0b\n\x03key\x18\x01 \x01(\t\x12*\n\x05value\x18\x02 \x01(\x0b\x32\x1b.dexcontrol.FirmwareVersion:\x02\x38\x01\"\x9d\x01\n\x14SingleComponentState\x12\x11\n\tconnected\x18\x01 \x01(\x08\x12,\n\x07\x65nabled\x18\x02 \x01(\x0e\x32\x1b.dexcontrol.ComponentStatus\x12\x30\n\x0b\x65rror_state\x18\x03 \x01(\x0e\x32\x1b.dexcontrol.ComponentStatus\x12\x12\n\nerror_code\x18\x04 \x01(\t\"\x9b\x01\n\x0f\x43omponentStates\x12\x37\n\x06states\x18\x01 \x03(\x0b\x32\'.dexcontrol.ComponentStates.StatesEntry\x1aO\n\x0bStatesEntry\x12\x0b\n\x03key\x18\x01 \x01(\t\x12/\n\x05value\x18\x02 \x01(\x0b\x32 .dexcontrol.SingleComponentState:\x02\x38\x01*0\n\x0f\x43omponentStatus\x12\n\n\x06NORMAL\x10\x00\x12\x06\n\x02NA\x10\x01\x12\t\n\x05\x45RROR\x10\x02\x62\x06proto3')
29
+
30
+ _globals = globals()
31
+ _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals)
32
+ _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'dexcontrol_query_pb2', _globals)
33
+ if not _descriptor._USE_C_DESCRIPTORS:
34
+ DESCRIPTOR._loaded_options = None
35
+ _globals['_SOFTWAREVERSION_FIRMWAREVERSIONENTRY']._loaded_options = None
36
+ _globals['_SOFTWAREVERSION_FIRMWAREVERSIONENTRY']._serialized_options = b'8\001'
37
+ _globals['_COMPONENTSTATES_STATESENTRY']._loaded_options = None
38
+ _globals['_COMPONENTSTATES_STATESENTRY']._serialized_options = b'8\001'
39
+ _globals['_COMPONENTSTATUS']._serialized_start=1121
40
+ _globals['_COMPONENTSTATUS']._serialized_end=1169
41
+ _globals['_SETARMMODE']._serialized_start=38
42
+ _globals['_SETARMMODE']._serialized_end=128
43
+ _globals['_SETARMMODE_MODE']._serialized_start=95
44
+ _globals['_SETARMMODE_MODE']._serialized_end=128
45
+ _globals['_SETHEADMODE']._serialized_start=130
46
+ _globals['_SETHEADMODE']._serialized_end=220
47
+ _globals['_SETHEADMODE_MODE']._serialized_start=189
48
+ _globals['_SETHEADMODE_MODE']._serialized_end=220
49
+ _globals['_SETESTOP']._serialized_start=222
50
+ _globals['_SETESTOP']._serialized_end=248
51
+ _globals['_SETLED']._serialized_start=250
52
+ _globals['_SETLED']._serialized_end=274
53
+ _globals['_CLEARERROR']._serialized_start=277
54
+ _globals['_CLEARERROR']._serialized_end=407
55
+ _globals['_CLEARERROR_COMPONENT']._serialized_start=344
56
+ _globals['_CLEARERROR_COMPONENT']._serialized_end=407
57
+ _globals['_REBOOTCOMPONENT']._serialized_start=409
58
+ _globals['_REBOOTCOMPONENT']._serialized_end=530
59
+ _globals['_REBOOTCOMPONENT_COMPONENT']._serialized_start=486
60
+ _globals['_REBOOTCOMPONENT_COMPONENT']._serialized_end=530
61
+ _globals['_FIRMWAREVERSION']._serialized_start=532
62
+ _globals['_FIRMWAREVERSION']._serialized_end=620
63
+ _globals['_SOFTWAREVERSION']._serialized_start=623
64
+ _globals['_SOFTWAREVERSION']._serialized_end=801
65
+ _globals['_SOFTWAREVERSION_FIRMWAREVERSIONENTRY']._serialized_start=718
66
+ _globals['_SOFTWAREVERSION_FIRMWAREVERSIONENTRY']._serialized_end=801
67
+ _globals['_SINGLECOMPONENTSTATE']._serialized_start=804
68
+ _globals['_SINGLECOMPONENTSTATE']._serialized_end=961
69
+ _globals['_COMPONENTSTATES']._serialized_start=964
70
+ _globals['_COMPONENTSTATES']._serialized_end=1119
71
+ _globals['_COMPONENTSTATES_STATESENTRY']._serialized_start=1040
72
+ _globals['_COMPONENTSTATES_STATESENTRY']._serialized_end=1119
73
+ # @@protoc_insertion_point(module_scope)
@@ -0,0 +1,134 @@
1
+ from collections.abc import Mapping as _Mapping
2
+ from typing import ClassVar as _ClassVar
3
+ from typing import Optional as _Optional
4
+ from typing import Union as _Union
5
+
6
+ from google.protobuf import descriptor as _descriptor
7
+ from google.protobuf import message as _message
8
+ from google.protobuf.internal import containers as _containers
9
+ from google.protobuf.internal import enum_type_wrapper as _enum_type_wrapper
10
+
11
+ DESCRIPTOR: _descriptor.FileDescriptor
12
+
13
+ class ComponentStatus(int, metaclass=_enum_type_wrapper.EnumTypeWrapper):
14
+ __slots__ = ()
15
+ NORMAL: _ClassVar[ComponentStatus]
16
+ NA: _ClassVar[ComponentStatus]
17
+ ERROR: _ClassVar[ComponentStatus]
18
+ NORMAL: ComponentStatus
19
+ NA: ComponentStatus
20
+ ERROR: ComponentStatus
21
+
22
+ class SetArmMode(_message.Message):
23
+ __slots__ = ("mode",)
24
+ class Mode(int, metaclass=_enum_type_wrapper.EnumTypeWrapper):
25
+ __slots__ = ()
26
+ POSITION: _ClassVar[SetArmMode.Mode]
27
+ DISABLE: _ClassVar[SetArmMode.Mode]
28
+ POSITION: SetArmMode.Mode
29
+ DISABLE: SetArmMode.Mode
30
+ MODE_FIELD_NUMBER: _ClassVar[int]
31
+ mode: SetArmMode.Mode
32
+ def __init__(self, mode: _Optional[_Union[SetArmMode.Mode, str]] = ...) -> None: ...
33
+
34
+ class SetHeadMode(_message.Message):
35
+ __slots__ = ("mode",)
36
+ class Mode(int, metaclass=_enum_type_wrapper.EnumTypeWrapper):
37
+ __slots__ = ()
38
+ ENABLE: _ClassVar[SetHeadMode.Mode]
39
+ DISABLE: _ClassVar[SetHeadMode.Mode]
40
+ ENABLE: SetHeadMode.Mode
41
+ DISABLE: SetHeadMode.Mode
42
+ MODE_FIELD_NUMBER: _ClassVar[int]
43
+ mode: SetHeadMode.Mode
44
+ def __init__(self, mode: _Optional[_Union[SetHeadMode.Mode, str]] = ...) -> None: ...
45
+
46
+ class SetEstop(_message.Message):
47
+ __slots__ = ("enable",)
48
+ ENABLE_FIELD_NUMBER: _ClassVar[int]
49
+ enable: bool
50
+ def __init__(self, enable: bool = ...) -> None: ...
51
+
52
+ class SetLed(_message.Message):
53
+ __slots__ = ("enable",)
54
+ ENABLE_FIELD_NUMBER: _ClassVar[int]
55
+ enable: bool
56
+ def __init__(self, enable: bool = ...) -> None: ...
57
+
58
+ class ClearError(_message.Message):
59
+ __slots__ = ("component",)
60
+ class Component(int, metaclass=_enum_type_wrapper.EnumTypeWrapper):
61
+ __slots__ = ()
62
+ LEFT_ARM: _ClassVar[ClearError.Component]
63
+ RIGHT_ARM: _ClassVar[ClearError.Component]
64
+ HEAD: _ClassVar[ClearError.Component]
65
+ CHASSIS: _ClassVar[ClearError.Component]
66
+ LEFT_ARM: ClearError.Component
67
+ RIGHT_ARM: ClearError.Component
68
+ HEAD: ClearError.Component
69
+ CHASSIS: ClearError.Component
70
+ COMPONENT_FIELD_NUMBER: _ClassVar[int]
71
+ component: ClearError.Component
72
+ def __init__(self, component: _Optional[_Union[ClearError.Component, str]] = ...) -> None: ...
73
+
74
+ class RebootComponent(_message.Message):
75
+ __slots__ = ("component",)
76
+ class Component(int, metaclass=_enum_type_wrapper.EnumTypeWrapper):
77
+ __slots__ = ()
78
+ ARM: _ClassVar[RebootComponent.Component]
79
+ TORSO: _ClassVar[RebootComponent.Component]
80
+ CHASSIS: _ClassVar[RebootComponent.Component]
81
+ ARM: RebootComponent.Component
82
+ TORSO: RebootComponent.Component
83
+ CHASSIS: RebootComponent.Component
84
+ COMPONENT_FIELD_NUMBER: _ClassVar[int]
85
+ component: RebootComponent.Component
86
+ def __init__(self, component: _Optional[_Union[RebootComponent.Component, str]] = ...) -> None: ...
87
+
88
+ class FirmwareVersion(_message.Message):
89
+ __slots__ = ("hardware_version", "software_version", "main_hash")
90
+ HARDWARE_VERSION_FIELD_NUMBER: _ClassVar[int]
91
+ SOFTWARE_VERSION_FIELD_NUMBER: _ClassVar[int]
92
+ MAIN_HASH_FIELD_NUMBER: _ClassVar[int]
93
+ hardware_version: int
94
+ software_version: int
95
+ main_hash: str
96
+ def __init__(self, hardware_version: _Optional[int] = ..., software_version: _Optional[int] = ..., main_hash: _Optional[str] = ...) -> None: ...
97
+
98
+ class SoftwareVersion(_message.Message):
99
+ __slots__ = ("firmware_version",)
100
+ class FirmwareVersionEntry(_message.Message):
101
+ __slots__ = ("key", "value")
102
+ KEY_FIELD_NUMBER: _ClassVar[int]
103
+ VALUE_FIELD_NUMBER: _ClassVar[int]
104
+ key: str
105
+ value: FirmwareVersion
106
+ def __init__(self, key: _Optional[str] = ..., value: _Optional[_Union[FirmwareVersion, _Mapping]] = ...) -> None: ...
107
+ FIRMWARE_VERSION_FIELD_NUMBER: _ClassVar[int]
108
+ firmware_version: _containers.MessageMap[str, FirmwareVersion]
109
+ def __init__(self, firmware_version: _Optional[_Mapping[str, FirmwareVersion]] = ...) -> None: ...
110
+
111
+ class SingleComponentState(_message.Message):
112
+ __slots__ = ("connected", "enabled", "error_state", "error_code")
113
+ CONNECTED_FIELD_NUMBER: _ClassVar[int]
114
+ ENABLED_FIELD_NUMBER: _ClassVar[int]
115
+ ERROR_STATE_FIELD_NUMBER: _ClassVar[int]
116
+ ERROR_CODE_FIELD_NUMBER: _ClassVar[int]
117
+ connected: bool
118
+ enabled: ComponentStatus
119
+ error_state: ComponentStatus
120
+ error_code: str
121
+ def __init__(self, connected: bool = ..., enabled: _Optional[_Union[ComponentStatus, str]] = ..., error_state: _Optional[_Union[ComponentStatus, str]] = ..., error_code: _Optional[str] = ...) -> None: ...
122
+
123
+ class ComponentStates(_message.Message):
124
+ __slots__ = ("states",)
125
+ class StatesEntry(_message.Message):
126
+ __slots__ = ("key", "value")
127
+ KEY_FIELD_NUMBER: _ClassVar[int]
128
+ VALUE_FIELD_NUMBER: _ClassVar[int]
129
+ key: str
130
+ value: SingleComponentState
131
+ def __init__(self, key: _Optional[str] = ..., value: _Optional[_Union[SingleComponentState, _Mapping]] = ...) -> None: ...
132
+ STATES_FIELD_NUMBER: _ClassVar[int]
133
+ states: _containers.MessageMap[str, SingleComponentState]
134
+ def __init__(self, states: _Optional[_Mapping[str, SingleComponentState]] = ...) -> None: ...