From aa7f826eaf036a5bc06d43bf3937b5a57afcf8ec Mon Sep 17 00:00:00 2001 From: MikiTwenty <97092783+MikiTwenty@users.noreply.github.com> Date: Tue, 7 Jan 2025 13:06:45 +0100 Subject: [PATCH] Clear Git cache --- .gitignore | 72 +- LICENSE | 58 +- README zh.md | 242 +++--- README.md | 222 +++--- example/front_camera/camera_opencv.py | 82 +- example/front_camera/capture_image.py | 60 +- example/helloworld/publisher.py | 56 +- example/helloworld/subscriber.py | 40 +- example/helloworld/user_data.py | 18 +- example/high_level/read_highstate.py | 46 +- example/high_level/sportmode_test.py | 288 +++---- example/low_level/lowlevel_control.py | 118 +-- example/low_level/read_lowstate.py | 54 +- example/low_level/unitree_legged_const.py | 40 +- .../obstacles_avoid_switch.py | 186 ++--- example/vui_client/vui_client_example.py | 154 ++-- .../wireless_controller.py | 110 +-- requirements.txt | 4 +- setup.py | 38 +- unitree_sdk2py/__init__.py | 18 +- unitree_sdk2py/core/channel.py | 580 +++++++------- unitree_sdk2py/core/channel_config.py | 50 +- unitree_sdk2py/core/channel_name.py | 66 +- .../obstacles_avoid/obstacles_avoid_api.py | 34 +- .../obstacles_avoid/obstacles_avoid_client.py | 78 +- .../go2/robot_state/robot_state_api.py | 50 +- .../go2/robot_state/robot_state_client.py | 168 ++-- unitree_sdk2py/go2/sport/sport_api.py | 122 +-- unitree_sdk2py/go2/sport/sport_client.py | 726 +++++++++--------- unitree_sdk2py/go2/video/video_api.py | 32 +- unitree_sdk2py/go2/video/video_client.py | 46 +- unitree_sdk2py/go2/vui/vui_api.py | 42 +- unitree_sdk2py/go2/vui/vui_client.py | 170 ++-- unitree_sdk2py/idl/__init__.py | 20 +- .../idl/builtin_interfaces/__init__.py | 18 +- .../idl/builtin_interfaces/msg/__init__.py | 18 +- .../idl/builtin_interfaces/msg/dds_/_Time_.py | 56 +- .../builtin_interfaces/msg/dds_/__init__.py | 18 +- unitree_sdk2py/idl/default.py | 410 +++++----- unitree_sdk2py/idl/geometry_msgs/__init__.py | 18 +- .../idl/geometry_msgs/msg/__init__.py | 18 +- .../idl/geometry_msgs/msg/dds_/_Point32_.py | 58 +- .../geometry_msgs/msg/dds_/_PointStamped_.py | 62 +- .../idl/geometry_msgs/msg/dds_/_Point_.py | 58 +- .../idl/geometry_msgs/msg/dds_/_Pose2D_.py | 58 +- .../geometry_msgs/msg/dds_/_PoseStamped_.py | 64 +- .../msg/dds_/_PoseWithCovarianceStamped_.py | 64 +- .../msg/dds_/_PoseWithCovariance_.py | 56 +- .../idl/geometry_msgs/msg/dds_/_Pose_.py | 56 +- .../msg/dds_/_QuaternionStamped_.py | 64 +- .../geometry_msgs/msg/dds_/_Quaternion_.py | 60 +- .../geometry_msgs/msg/dds_/_TwistStamped_.py | 64 +- .../msg/dds_/_TwistWithCovarianceStamped_.py | 64 +- .../msg/dds_/_TwistWithCovariance_.py | 56 +- .../idl/geometry_msgs/msg/dds_/_Twist_.py | 56 +- .../idl/geometry_msgs/msg/dds_/_Vector3_.py | 58 +- .../idl/geometry_msgs/msg/dds_/__init__.py | 46 +- unitree_sdk2py/idl/nav_msgs/__init__.py | 18 +- unitree_sdk2py/idl/nav_msgs/msg/__init__.py | 18 +- .../idl/nav_msgs/msg/dds_/_MapMetaData_.py | 70 +- .../idl/nav_msgs/msg/dds_/_OccupancyGrid_.py | 66 +- .../idl/nav_msgs/msg/dds_/_Odometry_.py | 70 +- .../idl/nav_msgs/msg/dds_/__init__.py | 22 +- unitree_sdk2py/idl/sensor_msgs/__init__.py | 18 +- .../idl/sensor_msgs/msg/__init__.py | 18 +- .../dds_/PointField_Constants/_PointField_.py | 56 +- .../msg/dds_/PointField_Constants/__init__.py | 18 +- .../idl/sensor_msgs/msg/dds_/_PointCloud2_.py | 78 +- .../idl/sensor_msgs/msg/dds_/_PointField_.py | 60 +- .../idl/sensor_msgs/msg/dds_/__init__.py | 22 +- unitree_sdk2py/idl/std_msgs/__init__.py | 18 +- unitree_sdk2py/idl/std_msgs/msg/__init__.py | 18 +- .../idl/std_msgs/msg/dds_/_Header_.py | 64 +- .../idl/std_msgs/msg/dds_/_String_.py | 54 +- .../idl/std_msgs/msg/dds_/__init__.py | 20 +- unitree_sdk2py/idl/unitree_api/__init__.py | 18 +- .../idl/unitree_api/msg/__init__.py | 18 +- .../unitree_api/msg/dds_/_RequestHeader_.py | 58 +- .../unitree_api/msg/dds_/_RequestIdentity_.py | 56 +- .../unitree_api/msg/dds_/_RequestLease_.py | 54 +- .../unitree_api/msg/dds_/_RequestPolicy_.py | 56 +- .../idl/unitree_api/msg/dds_/_Request_.py | 56 +- .../unitree_api/msg/dds_/_ResponseHeader_.py | 56 +- .../unitree_api/msg/dds_/_ResponseStatus_.py | 54 +- .../idl/unitree_api/msg/dds_/_Response_.py | 56 +- .../idl/unitree_api/msg/dds_/__init__.py | 32 +- unitree_sdk2py/idl/unitree_go/__init__.py | 18 +- unitree_sdk2py/idl/unitree_go/msg/__init__.py | 18 +- .../idl/unitree_go/msg/dds_/_AudioData_.py | 56 +- .../idl/unitree_go/msg/dds_/_BmsCmd_.py | 56 +- .../idl/unitree_go/msg/dds_/_BmsState_.py | 70 +- .../idl/unitree_go/msg/dds_/_Error_.py | 56 +- .../msg/dds_/_Go2FrontVideoData_.py | 60 +- .../idl/unitree_go/msg/dds_/_HeightMap_.py | 66 +- .../idl/unitree_go/msg/dds_/_IMUState_.py | 62 +- .../unitree_go/msg/dds_/_InterfaceConfig_.py | 58 +- .../idl/unitree_go/msg/dds_/_LidarState_.py | 86 +-- .../idl/unitree_go/msg/dds_/_LowCmd_.py | 80 +- .../idl/unitree_go/msg/dds_/_LowState_.py | 96 +-- .../idl/unitree_go/msg/dds_/_MotorCmd_.py | 66 +- .../idl/unitree_go/msg/dds_/_MotorState_.py | 74 +- .../idl/unitree_go/msg/dds_/_PathPoint_.py | 66 +- .../idl/unitree_go/msg/dds_/_Req_.py | 56 +- .../idl/unitree_go/msg/dds_/_Res_.py | 58 +- .../unitree_go/msg/dds_/_SportModeState_.py | 84 +- .../idl/unitree_go/msg/dds_/_TimeSpec_.py | 56 +- .../idl/unitree_go/msg/dds_/_UwbState_.py | 86 +-- .../idl/unitree_go/msg/dds_/_UwbSwitch_.py | 54 +- .../msg/dds_/_WirelessController_.py | 62 +- .../idl/unitree_go/msg/dds_/__init__.py | 58 +- unitree_sdk2py/rpc/client.py | 176 ++--- unitree_sdk2py/rpc/client_base.py | 186 ++--- unitree_sdk2py/rpc/client_stub.py | 138 ++-- unitree_sdk2py/rpc/internal.py | 62 +- unitree_sdk2py/rpc/lease_client.py | 226 +++--- unitree_sdk2py/rpc/lease_server.py | 300 ++++---- unitree_sdk2py/rpc/request_future.py | 90 +-- unitree_sdk2py/rpc/server.py | 242 +++--- unitree_sdk2py/rpc/server_base.py | 64 +- unitree_sdk2py/rpc/server_stub.py | 156 ++-- .../client/obstacles_avoid_client_example.py | 180 ++--- .../client/robot_service_client_example.py | 100 +-- .../test/client/sport_client_example.py | 218 +++--- .../test/client/video_client_example.py | 52 +- .../test/client/vui_client_example.py | 148 ++-- unitree_sdk2py/test/crc/test_crc.py | 30 +- unitree_sdk2py/test/helloworld/helloworld.py | 10 +- unitree_sdk2py/test/helloworld/publisher.py | 42 +- unitree_sdk2py/test/helloworld/subscriber.py | 36 +- .../test/lowlevel/lowlevel_control.py | 102 +-- unitree_sdk2py/test/lowlevel/read_lowstate.py | 48 +- unitree_sdk2py/test/lowlevel/sub_lowstate.py | 28 +- .../test/lowlevel/unitree_go2_const.py | 40 +- unitree_sdk2py/test/rpc/test_api.py | 16 +- .../test/rpc/test_client_example.py | 124 +-- .../test/rpc/test_server_example.py | 88 +-- unitree_sdk2py/utils/bqueue.py | 116 +-- unitree_sdk2py/utils/clib_lookup.py | 34 +- unitree_sdk2py/utils/crc.py | 280 +++---- unitree_sdk2py/utils/future.py | 206 ++--- unitree_sdk2py/utils/hz_sample.py | 48 +- unitree_sdk2py/utils/singleton.py | 22 +- unitree_sdk2py/utils/thread.py | 166 ++-- unitree_sdk2py/utils/timerfd.py | 90 +-- 144 files changed, 6089 insertions(+), 6089 deletions(-) diff --git a/.gitignore b/.gitignore index 9871dce..7bfe75d 100644 --- a/.gitignore +++ b/.gitignore @@ -1,36 +1,36 @@ -# Generated by MacOS -.DS_Store - -# Generated by Windows -Thumbs.db - -# Applications -*.app -*.exe -*.war - -# Large media files -*.mp4 -*.tiff -*.avi -*.flv -*.mov -*.wmv -*.jpg -*.png - -# VS Code -.vscode - -# other -*.egg-info -__pycache__ - -# IDEs -.idea - -# cache -.pytest_cache - -# JetBrains IDE -.idea/ +# Generated by MacOS +.DS_Store + +# Generated by Windows +Thumbs.db + +# Applications +*.app +*.exe +*.war + +# Large media files +*.mp4 +*.tiff +*.avi +*.flv +*.mov +*.wmv +*.jpg +*.png + +# VS Code +.vscode + +# other +*.egg-info +__pycache__ + +# IDEs +.idea + +# cache +.pytest_cache + +# JetBrains IDE +.idea/ diff --git a/LICENSE b/LICENSE index 42d2e64..048f970 100644 --- a/LICENSE +++ b/LICENSE @@ -1,29 +1,29 @@ -BSD 3-Clause License - -Copyright (c) 2016-2024 HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics") -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -* Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -* Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -* Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +BSD 3-Clause License + +Copyright (c) 2016-2024 HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics") +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/README zh.md b/README zh.md index 66989c8..b40f415 100644 --- a/README zh.md +++ b/README zh.md @@ -1,121 +1,121 @@ -# unitree_sdk2_python -unitree_sdk2 python 接口 - -# 安装 -## 依赖 -- python>=3.8,<3.11 -- cyclonedds==0.10.2 -- numpy -- opencv-python - -## 安装 unitree_sdk2_python -在终端中执行: -```bash -cd ~ -sudo apt install python3-pip -git clone https://github.com/unitreerobotics/unitree_sdk2_python.git -cd unitree_sdk2_python -pip3 install -e . -``` -## FAQ -##### 1. `pip3 install -e .` 遇到报错 -```bash -Could not locate cyclonedds. Try to set CYCLONEDDS_HOME or CMAKE_PREFIX_PATH -``` -该错误提示找不到 cyclonedds 路径。首先编译安装cyclonedds: -```bash -cd ~ -git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x -cd cyclonedds && mkdir build install && cd build -cmake .. -DCMAKE_INSTALL_PREFIX=../install -cmake --build . --target install -``` -进入 unitree_sdk2_python 目录,设置 `CYCLONEDDS_HOME` 为刚刚编译好的 cyclonedds 所在路径,再安装 unitree_sdk2_python -```bash -cd ~/unitree_sdk2_python -export CYCLONEDDS_HOME="~/cyclonedds/install" -pip3 install -e . -``` - -详细见: -https://pypi.org/project/cyclonedds/#installing-with-pre-built-binaries - -# 使用 -python sdk2 接口与 unitree_skd2的接口保持一致,通过请求响应或订阅发布topic实现机器人的状态获取和控制。相应的例程位于`/example`目录下。在运行例程前,需要根据文档 https://support.unitree.com/home/zh/developer/Quick_start 配置好机器人的网络连接。 -## DDS通讯 -在终端中执行: -```bash -python3 ./example/helloworld/publisher.py -``` -打开新的终端,执行: -```bash -python3 ./example/helloworld/subscriber.py -``` -可以看到终端输出的数据信息。`publisher.py` 和 `subscriber.py` 传输的数据定义在 `user_data.py` 中,用户可以根据需要自行定义需要传输的数据结构。 - -## 高层状态和控制 -高层接口的数据结构和控制方式与unitree_sdk2一致。具体可见:https://support.unitree.com/home/zh/developer/sports_services -### 高层状态 -终端中执行: -```bash -python3 ./example/high_level/read_highstate.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 -### 高层控制 -终端中执行: -```bash -python3 ./example/high_level/sportmode_test.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 -该例程提供了几种测试方法,可根据测试需要选择: -```python -test.StandUpDown() # 站立趴下 -# test.VelocityMove() # 速度控制 -# test.BalanceAttitude() # 姿态控制 -# test.TrajectoryFollow() # 轨迹跟踪 -# test.SpecialMotions() # 特殊动作 - -``` -## 底层状态和控制 -底层接口的数据结构和控制方式与unitree_sdk2一致。具体可见:https://support.unitree.com/home/zh/developer/Basic_services -### 底层状态 -终端中执行: -```bash -python3 ./example/low_level/lowlevel_control.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。程序会输出右前腿hip关节的状态、IMU和电池电压信息。 - -### 底层电机控制 -首先使用 app 关闭高层运动服务(sport_mode),否则会导致指令冲突。 -终端中执行: -```bash -python3 ./example/low_level/lowlevel_control.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。左后腿 hip 关节会保持在0角度 (安全起见,这里设置 kp=10, kd=1),左后腿 calf 关节将持续输出 1Nm 的转矩。 - -## 遥控器状态获取 -终端中执行: -```bash -python3 ./example/wireless_controller/wireless_controller.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 -终端将输出每一个按键的状态。对于遥控器按键的定义和数据结构可见: https://support.unitree.com/home/zh/developer/Get_remote_control_status - -## 前置摄像头 -使用opencv获取前置摄像头(确保在有图形界面的系统下运行, 按 ESC 退出程序): -```bash -python3 ./example/front_camera/camera_opencv.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 - -## 避障开关 -```bash -python3 ./example/obstacles_avoid_switch/obstacles_avoid_switch.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。机器人将循环开启和关闭避障功能。关于避障服务,详细见 https://support.unitree.com/home/zh/developer/ObstaclesAvoidClient - -## 灯光音量控制 -```bash -python3 ./example/vui_client/vui_client_example.py enp2s0 -``` -其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。机器人将循环调节音量和灯光亮度。该接口详细见 https://support.unitree.com/home/zh/developer/VuiClient +# unitree_sdk2_python +unitree_sdk2 python 接口 + +# 安装 +## 依赖 +- python>=3.8,<3.11 +- cyclonedds==0.10.2 +- numpy +- opencv-python + +## 安装 unitree_sdk2_python +在终端中执行: +```bash +cd ~ +sudo apt install python3-pip +git clone https://github.com/unitreerobotics/unitree_sdk2_python.git +cd unitree_sdk2_python +pip3 install -e . +``` +## FAQ +##### 1. `pip3 install -e .` 遇到报错 +```bash +Could not locate cyclonedds. Try to set CYCLONEDDS_HOME or CMAKE_PREFIX_PATH +``` +该错误提示找不到 cyclonedds 路径。首先编译安装cyclonedds: +```bash +cd ~ +git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x +cd cyclonedds && mkdir build install && cd build +cmake .. -DCMAKE_INSTALL_PREFIX=../install +cmake --build . --target install +``` +进入 unitree_sdk2_python 目录,设置 `CYCLONEDDS_HOME` 为刚刚编译好的 cyclonedds 所在路径,再安装 unitree_sdk2_python +```bash +cd ~/unitree_sdk2_python +export CYCLONEDDS_HOME="~/cyclonedds/install" +pip3 install -e . +``` + +详细见: +https://pypi.org/project/cyclonedds/#installing-with-pre-built-binaries + +# 使用 +python sdk2 接口与 unitree_skd2的接口保持一致,通过请求响应或订阅发布topic实现机器人的状态获取和控制。相应的例程位于`/example`目录下。在运行例程前,需要根据文档 https://support.unitree.com/home/zh/developer/Quick_start 配置好机器人的网络连接。 +## DDS通讯 +在终端中执行: +```bash +python3 ./example/helloworld/publisher.py +``` +打开新的终端,执行: +```bash +python3 ./example/helloworld/subscriber.py +``` +可以看到终端输出的数据信息。`publisher.py` 和 `subscriber.py` 传输的数据定义在 `user_data.py` 中,用户可以根据需要自行定义需要传输的数据结构。 + +## 高层状态和控制 +高层接口的数据结构和控制方式与unitree_sdk2一致。具体可见:https://support.unitree.com/home/zh/developer/sports_services +### 高层状态 +终端中执行: +```bash +python3 ./example/high_level/read_highstate.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 +### 高层控制 +终端中执行: +```bash +python3 ./example/high_level/sportmode_test.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 +该例程提供了几种测试方法,可根据测试需要选择: +```python +test.StandUpDown() # 站立趴下 +# test.VelocityMove() # 速度控制 +# test.BalanceAttitude() # 姿态控制 +# test.TrajectoryFollow() # 轨迹跟踪 +# test.SpecialMotions() # 特殊动作 + +``` +## 底层状态和控制 +底层接口的数据结构和控制方式与unitree_sdk2一致。具体可见:https://support.unitree.com/home/zh/developer/Basic_services +### 底层状态 +终端中执行: +```bash +python3 ./example/low_level/lowlevel_control.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。程序会输出右前腿hip关节的状态、IMU和电池电压信息。 + +### 底层电机控制 +首先使用 app 关闭高层运动服务(sport_mode),否则会导致指令冲突。 +终端中执行: +```bash +python3 ./example/low_level/lowlevel_control.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。左后腿 hip 关节会保持在0角度 (安全起见,这里设置 kp=10, kd=1),左后腿 calf 关节将持续输出 1Nm 的转矩。 + +## 遥控器状态获取 +终端中执行: +```bash +python3 ./example/wireless_controller/wireless_controller.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 +终端将输出每一个按键的状态。对于遥控器按键的定义和数据结构可见: https://support.unitree.com/home/zh/developer/Get_remote_control_status + +## 前置摄像头 +使用opencv获取前置摄像头(确保在有图形界面的系统下运行, 按 ESC 退出程序): +```bash +python3 ./example/front_camera/camera_opencv.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。 + +## 避障开关 +```bash +python3 ./example/obstacles_avoid_switch/obstacles_avoid_switch.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。机器人将循环开启和关闭避障功能。关于避障服务,详细见 https://support.unitree.com/home/zh/developer/ObstaclesAvoidClient + +## 灯光音量控制 +```bash +python3 ./example/vui_client/vui_client_example.py enp2s0 +``` +其中 `enp2s0` 为机器人所连接的网卡名称,请根据实际情况修改。机器人将循环调节音量和灯光亮度。该接口详细见 https://support.unitree.com/home/zh/developer/VuiClient diff --git a/README.md b/README.md index 9d4f5d8..9bcb6b5 100644 --- a/README.md +++ b/README.md @@ -1,112 +1,112 @@ -# unitree_sdk2_python -Python interface for unitree sdk2 - -# Installation -## Dependencies -- Python >= 3.8, < 3.11 -- cyclonedds == 0.10.2 -- numpy -- opencv-python -## Install unitree_sdk2_python -Execute the following commands in the terminal: -```bash -cd ~ -sudo apt install python3-pip -git clone https://github.com/unitreerobotics/unitree_sdk2_python.git -cd unitree_sdk2_python -pip3 install -e . -``` -## FAQ -##### 1. Error when `pip3 install -e .`: -```bash -Could not locate cyclonedds. Try to set CYCLONEDDS_HOME or CMAKE_PREFIX_PATH -``` -This error mentions that the cyclonedds path could not be found. First compile and install cyclonedds: - -```bash -cd ~ -git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x -cd cyclonedds && mkdir build install && cd build -cmake .. -DCMAKE_INSTALL_PREFIX=../install -cmake --build . --target install -``` -Enter the unitree_sdk2_python directory, set `CYCLONEDDS_HOME` to the path of the cyclonedds you just compiled, and then install unitree_sdk2_python. -```bash -cd ~/unitree_sdk2_python -export CYCLONEDDS_HOME="~/cyclonedds/install" -pip3 install -e . -``` -For details, see: https://pypi.org/project/cyclonedds/#installing-with-pre-built-binaries - -# Usage -The Python sdk2 interface maintains consistency with the unitree_sdk2 interface, achieving robot status acquisition and control through request-response or topic subscription/publishing. Example programs are located in the `/example` directory. Before running the examples, configure the robot's network connection as per the instructions in the document at https://support.unitree.com/home/en/developer/Quick_start. -## DDS Communication -In the terminal, execute: -```bash -python3 ./example/helloworld/publisher.py -``` -Open a new terminal and execute: -```bash -python3 ./example/helloworld/subscriber.py -``` -You will see the data output in the terminal. The data structure transmitted between `publisher.py` and `subscriber.py` is defined in `user_data.py`, and users can define the required data structure as needed. -## High-Level Status and Control -The high-level interface maintains consistency with unitree_sdk2 in terms of data structure and control methods. For detailed information, refer to https://support.unitree.com/home/en/developer/sports_services. -### High-Level Status -Execute the following command in the terminal: -```bash -python3 ./example/high_level/read_highstate.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected,. -### High-Level Control -Execute the following command in the terminal: -```bash -python3 ./example/high_level/sportmode_test.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected. This example program provides several test methods, and you can choose the required tests as follows: -```python -test.StandUpDown() # Stand up and lie down -# test.VelocityMove() # Velocity control -# test.BalanceAttitude() # Attitude control -# test.TrajectoryFollow() # Trajectory tracking -# test.SpecialMotions() # Special motions -``` -## Low-Level Status and Control -The low-level interface maintains consistency with unitree_sdk2 in terms of data structure and control methods. For detailed information, refer to https://support.unitree.com/home/en/developer/Basic_services. -### Low-Level Status -Execute the following command in the terminal: -```bash -python3 ./example/low_level/lowlevel_control.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected. The program will output the state of the right front leg hip joint, IMU, and battery voltage. -### Low-Level Motor Control -First, use the app to turn off the high-level motion service (sport_mode) to prevent conflicting instructions. -Execute the following command in the terminal: -```bash -python3 ./example/low_level/lowlevel_control.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected. The left hind leg hip joint will maintain a 0-degree position (for safety, set kp=10, kd=1), and the left hind leg calf joint will continuously output 1Nm of torque. -## Wireless Controller Status -Execute the following command in the terminal: -```bash -python3 ./example/wireless_controller/wireless_controller.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected. The terminal will output the status of each key. For the definition and data structure of the remote control keys, refer to https://support.unitree.com/home/en/developer/Get_remote_control_status. -## Front Camera -Use OpenCV to obtain the front camera (ensure to run on a system with a graphical interface, and press ESC to exit the program): -```bash -python3 ./example/front_camera/camera_opencv.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected. - -## Obstacle Avoidance Switch -```bash -python3 ./example/obstacles_avoid_switch/obstacles_avoid_switch.py enp2s0 -``` -Replace `enp2s0` with the name of the network interface to which the robot is connected. The robot will cycle obstacle avoidance on and off. For details on the obstacle avoidance service, see https://support.unitree.com/home/en/developer/ObstaclesAvoidClient - -## Light and volume control -```bash -python3 ./example/vui_client/vui_client_example.py enp2s0 -``` +# unitree_sdk2_python +Python interface for unitree sdk2 + +# Installation +## Dependencies +- Python >= 3.8, < 3.11 +- cyclonedds == 0.10.2 +- numpy +- opencv-python +## Install unitree_sdk2_python +Execute the following commands in the terminal: +```bash +cd ~ +sudo apt install python3-pip +git clone https://github.com/unitreerobotics/unitree_sdk2_python.git +cd unitree_sdk2_python +pip3 install -e . +``` +## FAQ +##### 1. Error when `pip3 install -e .`: +```bash +Could not locate cyclonedds. Try to set CYCLONEDDS_HOME or CMAKE_PREFIX_PATH +``` +This error mentions that the cyclonedds path could not be found. First compile and install cyclonedds: + +```bash +cd ~ +git clone https://github.com/eclipse-cyclonedds/cyclonedds -b releases/0.10.x +cd cyclonedds && mkdir build install && cd build +cmake .. -DCMAKE_INSTALL_PREFIX=../install +cmake --build . --target install +``` +Enter the unitree_sdk2_python directory, set `CYCLONEDDS_HOME` to the path of the cyclonedds you just compiled, and then install unitree_sdk2_python. +```bash +cd ~/unitree_sdk2_python +export CYCLONEDDS_HOME="~/cyclonedds/install" +pip3 install -e . +``` +For details, see: https://pypi.org/project/cyclonedds/#installing-with-pre-built-binaries + +# Usage +The Python sdk2 interface maintains consistency with the unitree_sdk2 interface, achieving robot status acquisition and control through request-response or topic subscription/publishing. Example programs are located in the `/example` directory. Before running the examples, configure the robot's network connection as per the instructions in the document at https://support.unitree.com/home/en/developer/Quick_start. +## DDS Communication +In the terminal, execute: +```bash +python3 ./example/helloworld/publisher.py +``` +Open a new terminal and execute: +```bash +python3 ./example/helloworld/subscriber.py +``` +You will see the data output in the terminal. The data structure transmitted between `publisher.py` and `subscriber.py` is defined in `user_data.py`, and users can define the required data structure as needed. +## High-Level Status and Control +The high-level interface maintains consistency with unitree_sdk2 in terms of data structure and control methods. For detailed information, refer to https://support.unitree.com/home/en/developer/sports_services. +### High-Level Status +Execute the following command in the terminal: +```bash +python3 ./example/high_level/read_highstate.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected,. +### High-Level Control +Execute the following command in the terminal: +```bash +python3 ./example/high_level/sportmode_test.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected. This example program provides several test methods, and you can choose the required tests as follows: +```python +test.StandUpDown() # Stand up and lie down +# test.VelocityMove() # Velocity control +# test.BalanceAttitude() # Attitude control +# test.TrajectoryFollow() # Trajectory tracking +# test.SpecialMotions() # Special motions +``` +## Low-Level Status and Control +The low-level interface maintains consistency with unitree_sdk2 in terms of data structure and control methods. For detailed information, refer to https://support.unitree.com/home/en/developer/Basic_services. +### Low-Level Status +Execute the following command in the terminal: +```bash +python3 ./example/low_level/lowlevel_control.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected. The program will output the state of the right front leg hip joint, IMU, and battery voltage. +### Low-Level Motor Control +First, use the app to turn off the high-level motion service (sport_mode) to prevent conflicting instructions. +Execute the following command in the terminal: +```bash +python3 ./example/low_level/lowlevel_control.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected. The left hind leg hip joint will maintain a 0-degree position (for safety, set kp=10, kd=1), and the left hind leg calf joint will continuously output 1Nm of torque. +## Wireless Controller Status +Execute the following command in the terminal: +```bash +python3 ./example/wireless_controller/wireless_controller.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected. The terminal will output the status of each key. For the definition and data structure of the remote control keys, refer to https://support.unitree.com/home/en/developer/Get_remote_control_status. +## Front Camera +Use OpenCV to obtain the front camera (ensure to run on a system with a graphical interface, and press ESC to exit the program): +```bash +python3 ./example/front_camera/camera_opencv.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected. + +## Obstacle Avoidance Switch +```bash +python3 ./example/obstacles_avoid_switch/obstacles_avoid_switch.py enp2s0 +``` +Replace `enp2s0` with the name of the network interface to which the robot is connected. The robot will cycle obstacle avoidance on and off. For details on the obstacle avoidance service, see https://support.unitree.com/home/en/developer/ObstaclesAvoidClient + +## Light and volume control +```bash +python3 ./example/vui_client/vui_client_example.py enp2s0 +``` Replace `enp2s0` with the name of the network interface to which the robot is connected.T he robot will cycle the volume and light brightness. The interface is detailed at https://support.unitree.com/home/en/developer/VuiClient \ No newline at end of file diff --git a/example/front_camera/camera_opencv.py b/example/front_camera/camera_opencv.py index 9d98839..e220e6f 100644 --- a/example/front_camera/camera_opencv.py +++ b/example/front_camera/camera_opencv.py @@ -1,41 +1,41 @@ -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.video.video_client import VideoClient -import cv2 -import numpy as np -import sys - - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - - client = VideoClient() # Create a video client - client.SetTimeout(3.0) - client.Init() - - code, data = client.GetImageSample() - - # Request normal when code==0 - while code == 0: - # Get Image data from Go2 robot - code, data = client.GetImageSample() - - # Convert to numpy image - image_data = np.frombuffer(bytes(data), dtype=np.uint8) - image = cv2.imdecode(image_data, cv2.IMREAD_COLOR) - - # Display image - cv2.imshow("front_camera", image) - # Press ESC to stop - if cv2.waitKey(20) == 27: - break - - if code != 0: - print("Get image sample error. code:", code) - else: - # Capture an image - cv2.imwrite("front_image.jpg", image) - - cv2.destroyWindow("front_camera") +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.video.video_client import VideoClient +import cv2 +import numpy as np +import sys + + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + + client = VideoClient() # Create a video client + client.SetTimeout(3.0) + client.Init() + + code, data = client.GetImageSample() + + # Request normal when code==0 + while code == 0: + # Get Image data from Go2 robot + code, data = client.GetImageSample() + + # Convert to numpy image + image_data = np.frombuffer(bytes(data), dtype=np.uint8) + image = cv2.imdecode(image_data, cv2.IMREAD_COLOR) + + # Display image + cv2.imshow("front_camera", image) + # Press ESC to stop + if cv2.waitKey(20) == 27: + break + + if code != 0: + print("Get image sample error. code:", code) + else: + # Capture an image + cv2.imwrite("front_image.jpg", image) + + cv2.destroyWindow("front_camera") diff --git a/example/front_camera/capture_image.py b/example/front_camera/capture_image.py index 1e85643..4e284b3 100644 --- a/example/front_camera/capture_image.py +++ b/example/front_camera/capture_image.py @@ -1,30 +1,30 @@ -import time -import os -import sys - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.video.video_client import VideoClient - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - - client = VideoClient() - client.SetTimeout(3.0) - client.Init() - - print("##################GetImageSample###################") - code, data = client.GetImageSample() - - if code != 0: - print("get image sample error. code:", code) - else: - imageName = "./img.jpg" - print("ImageName:", imageName) - - with open(imageName, "+wb") as f: - f.write(bytes(data)) - - time.sleep(1) +import time +import os +import sys + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.video.video_client import VideoClient + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + + client = VideoClient() + client.SetTimeout(3.0) + client.Init() + + print("##################GetImageSample###################") + code, data = client.GetImageSample() + + if code != 0: + print("get image sample error. code:", code) + else: + imageName = "./img.jpg" + print("ImageName:", imageName) + + with open(imageName, "+wb") as f: + f.write(bytes(data)) + + time.sleep(1) diff --git a/example/helloworld/publisher.py b/example/helloworld/publisher.py index cfe4f1f..1939d0d 100644 --- a/example/helloworld/publisher.py +++ b/example/helloworld/publisher.py @@ -1,28 +1,28 @@ -import time - -from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize -from user_data import * - - -if __name__ == "__main__": - ChannelFactoryInitialize() - - # Create a publisher to publish the data defined in UserData class - pub = ChannelPublisher("topic", UserData) - pub.Init() - - for i in range(30): - # Create a Userdata message - msg = UserData(" ", 0) - msg.string_data = "Hello world" - msg.float_data = time.time() - - # Publish message - if pub.Write(msg, 0.5): - print("Publish success. msg:", msg) - else: - print("Waitting for subscriber.") - - time.sleep(1) - - pub.Close() +import time + +from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize +from user_data import * + + +if __name__ == "__main__": + ChannelFactoryInitialize() + + # Create a publisher to publish the data defined in UserData class + pub = ChannelPublisher("topic", UserData) + pub.Init() + + for i in range(30): + # Create a Userdata message + msg = UserData(" ", 0) + msg.string_data = "Hello world" + msg.float_data = time.time() + + # Publish message + if pub.Write(msg, 0.5): + print("Publish success. msg:", msg) + else: + print("Waitting for subscriber.") + + time.sleep(1) + + pub.Close() diff --git a/example/helloworld/subscriber.py b/example/helloworld/subscriber.py index a7d0b63..510215b 100644 --- a/example/helloworld/subscriber.py +++ b/example/helloworld/subscriber.py @@ -1,20 +1,20 @@ -import time - -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from user_data import * - - -if __name__ == "__main__": - ChannelFactoryInitialize() - # Create a subscriber to subscribe the data defined in UserData class - sub = ChannelSubscriber("topic", UserData) - sub.Init() - - while True: - msg = sub.Read() - if msg is not None: - print("Subscribe success. msg:", msg) - else: - print("No data subscribed.") - break - sub.Close() +import time + +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from user_data import * + + +if __name__ == "__main__": + ChannelFactoryInitialize() + # Create a subscriber to subscribe the data defined in UserData class + sub = ChannelSubscriber("topic", UserData) + sub.Init() + + while True: + msg = sub.Read() + if msg is not None: + print("Subscribe success. msg:", msg) + else: + print("No data subscribed.") + break + sub.Close() diff --git a/example/helloworld/user_data.py b/example/helloworld/user_data.py index 9696ce3..dbe941e 100644 --- a/example/helloworld/user_data.py +++ b/example/helloworld/user_data.py @@ -1,9 +1,9 @@ -from dataclasses import dataclass -from cyclonedds.idl import IdlStruct - - -# This class defines user data consisting of a float data and a string data -@dataclass -class UserData(IdlStruct, typename="UserData"): - string_data: str - float_data: float +from dataclasses import dataclass +from cyclonedds.idl import IdlStruct + + +# This class defines user data consisting of a float data and a string data +@dataclass +class UserData(IdlStruct, typename="UserData"): + string_data: str + float_data: float diff --git a/example/high_level/read_highstate.py b/example/high_level/read_highstate.py index ba43a76..7bba115 100644 --- a/example/high_level/read_highstate.py +++ b/example/high_level/read_highstate.py @@ -1,23 +1,23 @@ -import time -import sys -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize - -from unitree_sdk2py.idl.default import unitree_go_msg_dds__SportModeState_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import SportModeState_ - - -def HighStateHandler(msg: SportModeState_): - print("Position: ", msg.position) - print("Velocity: ", msg.velocity) - print("Yaw velocity: ", msg.yaw_speed) - print("Foot position in body frame: ", msg.foot_position_body) - print("Foot velocity in body frame: ", msg.foot_speed_body) - - -if __name__ == "__main__": - ChannelFactoryInitialize(0, "enp3s0") - sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) - sub.Init(HighStateHandler, 10) - - while True: - time.sleep(10.0) +import time +import sys +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize + +from unitree_sdk2py.idl.default import unitree_go_msg_dds__SportModeState_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import SportModeState_ + + +def HighStateHandler(msg: SportModeState_): + print("Position: ", msg.position) + print("Velocity: ", msg.velocity) + print("Yaw velocity: ", msg.yaw_speed) + print("Foot position in body frame: ", msg.foot_position_body) + print("Foot velocity in body frame: ", msg.foot_speed_body) + + +if __name__ == "__main__": + ChannelFactoryInitialize(0, "enp3s0") + sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) + sub.Init(HighStateHandler, 10) + + while True: + time.sleep(10.0) diff --git a/example/high_level/sportmode_test.py b/example/high_level/sportmode_test.py index 845ddc5..795fbc8 100644 --- a/example/high_level/sportmode_test.py +++ b/example/high_level/sportmode_test.py @@ -1,144 +1,144 @@ -import time -import sys -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from unitree_sdk2py.idl.default import unitree_go_msg_dds__SportModeState_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import SportModeState_ -from unitree_sdk2py.go2.sport.sport_client import ( - SportClient, - PathPoint, - SPORT_PATH_POINT_SIZE, -) -import math - - -class SportModeTest: - def __init__(self) -> None: - # Time count - self.t = 0 - self.dt = 0.01 - - # Initial poition and yaw - self.px0 = 0 - self.py0 = 0 - self.yaw0 = 0 - - self.client = SportClient() # Create a sport client - self.client.SetTimeout(10.0) - self.client.Init() - - def GetInitState(self, robot_state: SportModeState_): - self.px0 = robot_state.position[0] - self.py0 = robot_state.position[1] - self.yaw0 = robot_state.imu_state.rpy[2] - - def StandUpDown(self): - self.client.StandDown() - print("Stand down !!!") - time.sleep(1) - - self.client.StandUp() - print("Stand up !!!") - time.sleep(1) - - self.client.StandDown() - print("Stand down !!!") - time.sleep(1) - - self.client.Damp() - - def VelocityMove(self): - elapsed_time = 1 - for i in range(int(elapsed_time / self.dt)): - self.client.Move(0.3, 0, 0.3) # vx, vy vyaw - time.sleep(self.dt) - self.client.StopMove() - - def BalanceAttitude(self): - self.client.Euler(0.1, 0.2, 0.3) # roll, pitch, yaw - self.client.BalanceStand() - - def TrajectoryFollow(self): - time_seg = 0.2 - time_temp = self.t - time_seg - path = [] - for i in range(SPORT_PATH_POINT_SIZE): - time_temp += time_seg - - px_local = 0.5 * math.sin(0.5 * time_temp) - py_local = 0 - yaw_local = 0 - vx_local = 0.25 * math.cos(0.5 * time_temp) - vy_local = 0 - vyaw_local = 0 - - path_point_tmp = PathPoint(0, 0, 0, 0, 0, 0, 0) - - path_point_tmp.timeFromStart = i * time_seg - path_point_tmp.x = ( - px_local * math.cos(self.yaw0) - - py_local * math.sin(self.yaw0) - + self.px0 - ) - path_point_tmp.y = ( - px_local * math.sin(self.yaw0) - + py_local * math.cos(self.yaw0) - + self.py0 - ) - path_point_tmp.yaw = yaw_local + self.yaw0 - path_point_tmp.vx = vx_local * math.cos(self.yaw0) - vy_local * math.sin( - self.yaw0 - ) - path_point_tmp.vy = vx_local * math.sin(self.yaw0) + vy_local * math.cos( - self.yaw0 - ) - path_point_tmp.vyaw = vyaw_local - - path.append(path_point_tmp) - - self.client.TrajectoryFollow(path) - - def SpecialMotions(self): - self.client.RecoveryStand() - print("RecoveryStand !!!") - time.sleep(1) - - self.client.Stretch() - print("Sit !!!") - time.sleep(1) - - self.client.RecoveryStand() - print("RecoveryStand !!!") - time.sleep(1) - - -# Robot state -robot_state = unitree_go_msg_dds__SportModeState_() -def HighStateHandler(msg: SportModeState_): - global robot_state - robot_state = msg - - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - - sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) - sub.Init(HighStateHandler, 10) - time.sleep(1) - - test = SportModeTest() - test.GetInitState(robot_state) - - print("Start test !!!") - while True: - test.t += test.dt - - test.StandUpDown() - # test.VelocityMove() - # test.BalanceAttitude() - # test.TrajectoryFollow() - # test.SpecialMotions() - - time.sleep(test.dt) +import time +import sys +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from unitree_sdk2py.idl.default import unitree_go_msg_dds__SportModeState_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import SportModeState_ +from unitree_sdk2py.go2.sport.sport_client import ( + SportClient, + PathPoint, + SPORT_PATH_POINT_SIZE, +) +import math + + +class SportModeTest: + def __init__(self) -> None: + # Time count + self.t = 0 + self.dt = 0.01 + + # Initial poition and yaw + self.px0 = 0 + self.py0 = 0 + self.yaw0 = 0 + + self.client = SportClient() # Create a sport client + self.client.SetTimeout(10.0) + self.client.Init() + + def GetInitState(self, robot_state: SportModeState_): + self.px0 = robot_state.position[0] + self.py0 = robot_state.position[1] + self.yaw0 = robot_state.imu_state.rpy[2] + + def StandUpDown(self): + self.client.StandDown() + print("Stand down !!!") + time.sleep(1) + + self.client.StandUp() + print("Stand up !!!") + time.sleep(1) + + self.client.StandDown() + print("Stand down !!!") + time.sleep(1) + + self.client.Damp() + + def VelocityMove(self): + elapsed_time = 1 + for i in range(int(elapsed_time / self.dt)): + self.client.Move(0.3, 0, 0.3) # vx, vy vyaw + time.sleep(self.dt) + self.client.StopMove() + + def BalanceAttitude(self): + self.client.Euler(0.1, 0.2, 0.3) # roll, pitch, yaw + self.client.BalanceStand() + + def TrajectoryFollow(self): + time_seg = 0.2 + time_temp = self.t - time_seg + path = [] + for i in range(SPORT_PATH_POINT_SIZE): + time_temp += time_seg + + px_local = 0.5 * math.sin(0.5 * time_temp) + py_local = 0 + yaw_local = 0 + vx_local = 0.25 * math.cos(0.5 * time_temp) + vy_local = 0 + vyaw_local = 0 + + path_point_tmp = PathPoint(0, 0, 0, 0, 0, 0, 0) + + path_point_tmp.timeFromStart = i * time_seg + path_point_tmp.x = ( + px_local * math.cos(self.yaw0) + - py_local * math.sin(self.yaw0) + + self.px0 + ) + path_point_tmp.y = ( + px_local * math.sin(self.yaw0) + + py_local * math.cos(self.yaw0) + + self.py0 + ) + path_point_tmp.yaw = yaw_local + self.yaw0 + path_point_tmp.vx = vx_local * math.cos(self.yaw0) - vy_local * math.sin( + self.yaw0 + ) + path_point_tmp.vy = vx_local * math.sin(self.yaw0) + vy_local * math.cos( + self.yaw0 + ) + path_point_tmp.vyaw = vyaw_local + + path.append(path_point_tmp) + + self.client.TrajectoryFollow(path) + + def SpecialMotions(self): + self.client.RecoveryStand() + print("RecoveryStand !!!") + time.sleep(1) + + self.client.Stretch() + print("Sit !!!") + time.sleep(1) + + self.client.RecoveryStand() + print("RecoveryStand !!!") + time.sleep(1) + + +# Robot state +robot_state = unitree_go_msg_dds__SportModeState_() +def HighStateHandler(msg: SportModeState_): + global robot_state + robot_state = msg + + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + + sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) + sub.Init(HighStateHandler, 10) + time.sleep(1) + + test = SportModeTest() + test.GetInitState(robot_state) + + print("Start test !!!") + while True: + test.t += test.dt + + test.StandUpDown() + # test.VelocityMove() + # test.BalanceAttitude() + # test.TrajectoryFollow() + # test.SpecialMotions() + + time.sleep(test.dt) diff --git a/example/low_level/lowlevel_control.py b/example/low_level/lowlevel_control.py index 638c5f2..9a2b8f2 100644 --- a/example/low_level/lowlevel_control.py +++ b/example/low_level/lowlevel_control.py @@ -1,60 +1,60 @@ -import time -import sys - -from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowCmd_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowCmd_ -from unitree_sdk2py.utils.crc import CRC -from unitree_sdk2py.utils.thread import Thread -import unitree_legged_const as go2 - -crc = CRC() - -if __name__ == '__main__': - - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - # Create a publisher to publish the data defined in UserData class - pub = ChannelPublisher("rt/lowcmd", LowCmd_) - pub.Init() - - cmd = unitree_go_msg_dds__LowCmd_() - cmd.head[0]=0xFE - cmd.head[1]=0xEF - cmd.level_flag = 0xFF - cmd.gpio = 0 - for i in range(20): - cmd.motor_cmd[i].mode = 0x01 # (PMSM) mode - cmd.motor_cmd[i].q= go2.PosStopF - cmd.motor_cmd[i].kp = 0 - cmd.motor_cmd[i].dq = go2.VelStopF - cmd.motor_cmd[i].kd = 0 - cmd.motor_cmd[i].tau = 0 - - while True: - # Toque controle, set RL_2 toque - cmd.motor_cmd[go2.LegID["RL_2"]].q = 0.0 # Set to stop position(rad) - cmd.motor_cmd[go2.LegID["RL_2"]].kp = 0.0 - cmd.motor_cmd[go2.LegID["RL_2"]].dq = 0.0 # Set to stop angular velocity(rad/s) - cmd.motor_cmd[go2.LegID["RL_2"]].kd = 0.0 - cmd.motor_cmd[go2.LegID["RL_2"]].tau = 1.0 # target toque is set to 1N.m - - # Poinstion(rad) control, set RL_0 rad - cmd.motor_cmd[go2.LegID["RL_0"]].q = 0.0 # Taregt angular(rad) - cmd.motor_cmd[go2.LegID["RL_0"]].kp = 10.0 # Poinstion(rad) control kp gain - cmd.motor_cmd[go2.LegID["RL_0"]].dq = 0.0 # Taregt angular velocity(rad/ss) - cmd.motor_cmd[go2.LegID["RL_0"]].kd = 1.0 # Poinstion(rad) control kd gain - cmd.motor_cmd[go2.LegID["RL_0"]].tau = 0.0 # Feedforward toque 1N.m - - cmd.crc = crc.Crc(cmd) - - #Publish message - if pub.Write(cmd): - print("Publish success. msg:", cmd.crc) - else: - print("Waitting for subscriber.") - +import time +import sys + +from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowCmd_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowCmd_ +from unitree_sdk2py.utils.crc import CRC +from unitree_sdk2py.utils.thread import Thread +import unitree_legged_const as go2 + +crc = CRC() + +if __name__ == '__main__': + + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + # Create a publisher to publish the data defined in UserData class + pub = ChannelPublisher("rt/lowcmd", LowCmd_) + pub.Init() + + cmd = unitree_go_msg_dds__LowCmd_() + cmd.head[0]=0xFE + cmd.head[1]=0xEF + cmd.level_flag = 0xFF + cmd.gpio = 0 + for i in range(20): + cmd.motor_cmd[i].mode = 0x01 # (PMSM) mode + cmd.motor_cmd[i].q= go2.PosStopF + cmd.motor_cmd[i].kp = 0 + cmd.motor_cmd[i].dq = go2.VelStopF + cmd.motor_cmd[i].kd = 0 + cmd.motor_cmd[i].tau = 0 + + while True: + # Toque controle, set RL_2 toque + cmd.motor_cmd[go2.LegID["RL_2"]].q = 0.0 # Set to stop position(rad) + cmd.motor_cmd[go2.LegID["RL_2"]].kp = 0.0 + cmd.motor_cmd[go2.LegID["RL_2"]].dq = 0.0 # Set to stop angular velocity(rad/s) + cmd.motor_cmd[go2.LegID["RL_2"]].kd = 0.0 + cmd.motor_cmd[go2.LegID["RL_2"]].tau = 1.0 # target toque is set to 1N.m + + # Poinstion(rad) control, set RL_0 rad + cmd.motor_cmd[go2.LegID["RL_0"]].q = 0.0 # Taregt angular(rad) + cmd.motor_cmd[go2.LegID["RL_0"]].kp = 10.0 # Poinstion(rad) control kp gain + cmd.motor_cmd[go2.LegID["RL_0"]].dq = 0.0 # Taregt angular velocity(rad/ss) + cmd.motor_cmd[go2.LegID["RL_0"]].kd = 1.0 # Poinstion(rad) control kd gain + cmd.motor_cmd[go2.LegID["RL_0"]].tau = 0.0 # Feedforward toque 1N.m + + cmd.crc = crc.Crc(cmd) + + #Publish message + if pub.Write(cmd): + print("Publish success. msg:", cmd.crc) + else: + print("Waitting for subscriber.") + time.sleep(0.002) \ No newline at end of file diff --git a/example/low_level/read_lowstate.py b/example/low_level/read_lowstate.py index 8653822..6fba6e6 100644 --- a/example/low_level/read_lowstate.py +++ b/example/low_level/read_lowstate.py @@ -1,27 +1,27 @@ -import time -import sys -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowState_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowState_ - -import unitree_legged_const as go2 - - -def LowStateHandler(msg: LowState_): - - # print front right hip motor states - print("FR_0 motor state: ", msg.motor_state[go2.LegID["FR_0"]]) - print("IMU state: ", msg.imu_state) - print("Battery state: voltage: ", msg.power_v, "current: ", msg.power_a) - - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - sub = ChannelSubscriber("rt/lowstate", LowState_) - sub.Init(LowStateHandler, 10) - - while True: - time.sleep(10.0) +import time +import sys +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowState_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowState_ + +import unitree_legged_const as go2 + + +def LowStateHandler(msg: LowState_): + + # print front right hip motor states + print("FR_0 motor state: ", msg.motor_state[go2.LegID["FR_0"]]) + print("IMU state: ", msg.imu_state) + print("Battery state: voltage: ", msg.power_v, "current: ", msg.power_a) + + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + sub = ChannelSubscriber("rt/lowstate", LowState_) + sub.Init(LowStateHandler, 10) + + while True: + time.sleep(10.0) diff --git a/example/low_level/unitree_legged_const.py b/example/low_level/unitree_legged_const.py index 153a051..dc130ca 100644 --- a/example/low_level/unitree_legged_const.py +++ b/example/low_level/unitree_legged_const.py @@ -1,20 +1,20 @@ -LegID = { - "FR_0": 0, # Front right hip - "FR_1": 1, # Front right thigh - "FR_2": 2, # Front right calf - "FL_0": 3, - "FL_1": 4, - "FL_2": 5, - "RR_0": 6, - "RR_1": 7, - "RR_2": 8, - "RL_0": 9, - "RL_1": 10, - "RL_2": 11, -} - -HIGHLEVEL = 0xEE -LOWLEVEL = 0xFF -TRIGERLEVEL = 0xF0 -PosStopF = 2.146e9 -VelStopF = 16000.0 +LegID = { + "FR_0": 0, # Front right hip + "FR_1": 1, # Front right thigh + "FR_2": 2, # Front right calf + "FL_0": 3, + "FL_1": 4, + "FL_2": 5, + "RR_0": 6, + "RR_1": 7, + "RR_2": 8, + "RL_0": 9, + "RL_1": 10, + "RL_2": 11, +} + +HIGHLEVEL = 0xEE +LOWLEVEL = 0xFF +TRIGERLEVEL = 0xF0 +PosStopF = 2.146e9 +VelStopF = 16000.0 diff --git a/example/obstacles_avoid_switch/obstacles_avoid_switch.py b/example/obstacles_avoid_switch/obstacles_avoid_switch.py index eb345c0..fcfeedf 100644 --- a/example/obstacles_avoid_switch/obstacles_avoid_switch.py +++ b/example/obstacles_avoid_switch/obstacles_avoid_switch.py @@ -1,94 +1,94 @@ -import time -import sys - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.obstacles_avoid.obstacles_avoid_client import ObstaclesAvoidClient - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - - client = ObstaclesAvoidClient() - client.SetTimeout(3.0) - client.Init() - - while True: - print("##################GetServerApiVersion###################") - code, serverAPiVersion = client.GetServerApiVersion() - if code != 0: - print("get server api error. code:", code) - else: - print("get server api version:", serverAPiVersion) - - if serverAPiVersion != client.GetApiVersion(): - print("api version not equal.") - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable) - - time.sleep(3) - - print("##################SwitchSet (on)###################") - code = client.SwitchSet(True) - if code != 0: - print("switch set error. code:", code) - else: - print("switch set success.") - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable1 = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable1) - - time.sleep(3) - - print("##################SwitchSet (off)###################") - code = client.SwitchSet(False) - if code != 0: - print("switch set error. code:", code) - else: - print("switch set success.") - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable1 = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable1) - - time.sleep(3) - - - print("##################SwitchSet (enable)###################") - - code = client.SwitchSet(enable) - if code != 0: - print("switch set error. code:", code) - else: - print("switch set success. enable:", enable) - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable) - - time.sleep(3) +import time +import sys + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.obstacles_avoid.obstacles_avoid_client import ObstaclesAvoidClient + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + + client = ObstaclesAvoidClient() + client.SetTimeout(3.0) + client.Init() + + while True: + print("##################GetServerApiVersion###################") + code, serverAPiVersion = client.GetServerApiVersion() + if code != 0: + print("get server api error. code:", code) + else: + print("get server api version:", serverAPiVersion) + + if serverAPiVersion != client.GetApiVersion(): + print("api version not equal.") + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable) + + time.sleep(3) + + print("##################SwitchSet (on)###################") + code = client.SwitchSet(True) + if code != 0: + print("switch set error. code:", code) + else: + print("switch set success.") + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable1 = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable1) + + time.sleep(3) + + print("##################SwitchSet (off)###################") + code = client.SwitchSet(False) + if code != 0: + print("switch set error. code:", code) + else: + print("switch set success.") + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable1 = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable1) + + time.sleep(3) + + + print("##################SwitchSet (enable)###################") + + code = client.SwitchSet(enable) + if code != 0: + print("switch set error. code:", code) + else: + print("switch set success. enable:", enable) + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable) + + time.sleep(3) \ No newline at end of file diff --git a/example/vui_client/vui_client_example.py b/example/vui_client/vui_client_example.py index a5e6932..5ba424c 100644 --- a/example/vui_client/vui_client_example.py +++ b/example/vui_client/vui_client_example.py @@ -1,77 +1,77 @@ -import time -import sys - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.vui.vui_client import VuiClient - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - - client = VuiClient() - client.SetTimeout(3.0) - client.Init() - - for i in range(1, 11): - print("#################GetBrightness####################") - code, level = client.GetBrightness() - - if code != 0: - print("get brightness error. code:", code) - else: - print("get brightness success. level:", level) - - time.sleep(1) - - print("#################SetBrightness####################") - - code = client.SetBrightness(i) - - if code != 0: - print("set brightness error. code:", code) - else: - print("set brightness success. level:", i) - - time.sleep(1) - - print("#################SetBrightness 0####################") - - code = client.SetBrightness(0) - - if code != 0: - print("set brightness error. code:", code) - else: - print("set brightness 0 success.") - - for i in range(1, 11): - print("#################GetVolume####################") - code, level = client.GetVolume() - - if code != 0: - print("get volume error. code:", code) - else: - print("get volume success. level:", level) - - time.sleep(1) - - print("#################SetVolume####################") - - code = client.SetVolume(i) - - if code != 0: - print("set volume error. code:", code) - else: - print("set volume success. level:", i) - - time.sleep(1) - - print("#################SetVolume 0####################") - - code = client.SetVolume(0) - - if code != 0: - print("set volume error. code:", code) - else: - print("set volume 0 success.") +import time +import sys + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.vui.vui_client import VuiClient + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + + client = VuiClient() + client.SetTimeout(3.0) + client.Init() + + for i in range(1, 11): + print("#################GetBrightness####################") + code, level = client.GetBrightness() + + if code != 0: + print("get brightness error. code:", code) + else: + print("get brightness success. level:", level) + + time.sleep(1) + + print("#################SetBrightness####################") + + code = client.SetBrightness(i) + + if code != 0: + print("set brightness error. code:", code) + else: + print("set brightness success. level:", i) + + time.sleep(1) + + print("#################SetBrightness 0####################") + + code = client.SetBrightness(0) + + if code != 0: + print("set brightness error. code:", code) + else: + print("set brightness 0 success.") + + for i in range(1, 11): + print("#################GetVolume####################") + code, level = client.GetVolume() + + if code != 0: + print("get volume error. code:", code) + else: + print("get volume success. level:", level) + + time.sleep(1) + + print("#################SetVolume####################") + + code = client.SetVolume(i) + + if code != 0: + print("set volume error. code:", code) + else: + print("set volume success. level:", i) + + time.sleep(1) + + print("#################SetVolume 0####################") + + code = client.SetVolume(0) + + if code != 0: + print("set volume error. code:", code) + else: + print("set volume 0 success.") diff --git a/example/wireless_controller/wireless_controller.py b/example/wireless_controller/wireless_controller.py index 0596d1a..1c32ccc 100644 --- a/example/wireless_controller/wireless_controller.py +++ b/example/wireless_controller/wireless_controller.py @@ -1,55 +1,55 @@ -import time -import sys -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize - -from unitree_sdk2py.idl.default import unitree_go_msg_dds__WirelessController_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import WirelessController_ - - -key_state = [ - ["R1", 0], - ["L1", 0], - ["start", 0], - ["select", 0], - ["R2", 0], - ["L2", 0], - ["F1", 0], - ["F2", 0], - ["A", 0], - ["B", 0], - ["X", 0], - ["Y", 0], - ["up", 0], - ["right", 0], - ["down", 0], - ["left", 0], -] - - -def WirelessControllerHandler(msg: WirelessController_): - global key_state - print("lx: ", msg.lx) - print("lx: ", msg.ly) - print("lx: ", msg.rx) - print("lx: ", msg.ry) - print("keys: ", msg.keys) - - #Update key state - for i in range(16): - key_state[i][1] = (msg.keys & (1 << i)) >> i - - print(key_state) - - - -if __name__ == "__main__": - if len(sys.argv)>1: - ChannelFactoryInitialize(0, sys.argv[1]) - else: - ChannelFactoryInitialize(0) - - sub = ChannelSubscriber("rt/wirelesscontroller", WirelessController_) - sub.Init(WirelessControllerHandler, 10) - - while True: - time.sleep(10.0) +import time +import sys +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize + +from unitree_sdk2py.idl.default import unitree_go_msg_dds__WirelessController_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import WirelessController_ + + +key_state = [ + ["R1", 0], + ["L1", 0], + ["start", 0], + ["select", 0], + ["R2", 0], + ["L2", 0], + ["F1", 0], + ["F2", 0], + ["A", 0], + ["B", 0], + ["X", 0], + ["Y", 0], + ["up", 0], + ["right", 0], + ["down", 0], + ["left", 0], +] + + +def WirelessControllerHandler(msg: WirelessController_): + global key_state + print("lx: ", msg.lx) + print("lx: ", msg.ly) + print("lx: ", msg.rx) + print("lx: ", msg.ry) + print("keys: ", msg.keys) + + #Update key state + for i in range(16): + key_state[i][1] = (msg.keys & (1 << i)) >> i + + print(key_state) + + + +if __name__ == "__main__": + if len(sys.argv)>1: + ChannelFactoryInitialize(0, sys.argv[1]) + else: + ChannelFactoryInitialize(0) + + sub = ChannelSubscriber("rt/wirelesscontroller", WirelessController_) + sub.Init(WirelessControllerHandler, 10) + + while True: + time.sleep(10.0) diff --git a/requirements.txt b/requirements.txt index 3b36aec..943575d 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,3 +1,3 @@ -numpy -opencv-python +numpy +opencv-python cyclonedds==0.10.2 \ No newline at end of file diff --git a/setup.py b/setup.py index 13e456b..ebd30e6 100644 --- a/setup.py +++ b/setup.py @@ -1,20 +1,20 @@ -from setuptools import setup, find_packages - - -def load_requirements(filename:str='requirements.txt') -> None: - with open(filename, 'r') as file: - return [line.strip() for line in file if line and not line.startswith("#")] - -requirements = load_requirements() - -setup( - name='unitree_sdk2py', - version='1.0.0', - author='Unitree', - author_email='unitree@unitree.com', - license="BSD-3-Clause", - packages=find_packages(), - description='Unitree robot sdk version 2 for python', - python_requires='>=3.8,<3.11', - install_requires=requirements +from setuptools import setup, find_packages + + +def load_requirements(filename:str='requirements.txt') -> None: + with open(filename, 'r') as file: + return [line.strip() for line in file if line and not line.startswith("#")] + +requirements = load_requirements() + +setup( + name='unitree_sdk2py', + version='1.0.0', + author='Unitree', + author_email='unitree@unitree.com', + license="BSD-3-Clause", + packages=find_packages(), + description='Unitree robot sdk version 2 for python', + python_requires='>=3.8,<3.11', + install_requires=requirements ) \ No newline at end of file diff --git a/unitree_sdk2py/__init__.py b/unitree_sdk2py/__init__.py index 316822f..d7a9a65 100644 --- a/unitree_sdk2py/__init__.py +++ b/unitree_sdk2py/__init__.py @@ -1,9 +1,9 @@ -from . import idl, utils, core, rpc, go2 - -__all__ = [ - "idl", - "utils", - "core", - "rpc", - "go2", -] +from . import idl, utils, core, rpc, go2 + +__all__ = [ + "idl", + "utils", + "core", + "rpc", + "go2", +] diff --git a/unitree_sdk2py/core/channel.py b/unitree_sdk2py/core/channel.py index d955f75..e80aea6 100644 --- a/unitree_sdk2py/core/channel.py +++ b/unitree_sdk2py/core/channel.py @@ -1,290 +1,290 @@ -import time -from typing import Any, Callable -from threading import Thread, Event - -from cyclonedds.domain import Domain, DomainParticipant -from cyclonedds.internal import dds_c_t -from cyclonedds.pub import DataWriter -from cyclonedds.sub import DataReader -from cyclonedds.topic import Topic -from cyclonedds.qos import Qos -from cyclonedds.core import DDSException, Listener -from cyclonedds.util import duration -from cyclonedds.internal import dds_c_t, InvalidSample - -# for channel config -from .channel_config import ChannelConfigAutoDetermine, ChannelConfigHasInterface - -# for singleton -from ..utils.singleton import Singleton -from ..utils.bqueue import BQueue - - -""" -" class ChannelReader -""" - -""" -" class Channel -""" -class Channel: - - """ - " internal class __Reader - """ - class __Reader: - def __init__(self): - self.__reader = None - self.__handler = None - self.__queue = None - self.__queueEnable = False - self.__threadEvent = None - self.__threadReader = None - - def Init(self, participant: DomainParticipant, topic: Topic, qos: Qos = None, handler: Callable = None, queueLen: int = 0): - if handler is None: - self.__reader = DataReader(participant, topic, qos) - else: - self.__handler = handler - if queueLen > 0: - self.__queueEnable = True - self.__queue = BQueue(queueLen) - self.__threadEvent = Event() - self.__threadReader = Thread(target=self.__ChannelReaderThreadFunc, name="ch_reader", daemon=True) - self.__threadReader.start() - self.__reader = DataReader(participant, topic, qos, Listener(on_data_available=self.__OnDataAvailable)) - - def Read(self, timeout: float = None): - sample = None - try: - if timeout is None: - sample = self.__reader.take_one() - else: - sample = self.__reader.take_one(timeout=duration(seconds=timeout)) - except DDSException as e: - print("[Reader] catch DDSException msg:", e.msg) - except TimeoutError as e: - print("[Reader] take sample timeout") - except: - print("[Reader] take sample error") - - return sample - - def Close(self): - if self.__reader is not None: - del self.__reader - - if self.__queueEnable: - self.__threadEvent.set() - self.__queue.Interrupt() - self.__queue.Clear() - self.__threadReader.join() - - def __OnDataAvailable(self, reader: DataReader): - samples = [] - try: - samples = reader.take(1) - except DDSException as e: - print("[Reader] catch DDSException error. msg:", e.msg) - return - except TimeoutError as e: - print("[Reader] take sample timeout") - return - except: - print("[Reader] take sample error") - return - - if samples is None: - return - - # check invalid sample - sample = samples[0] - if isinstance(sample, InvalidSample): - return - - # do sample - if self.__queueEnable: - self.__queue.Put(sample) - else: - self.__handler(sample) - - def __ChannelReaderThreadFunc(self): - while not self.__threadEvent.is_set(): - sample = self.__queue.Get() - if sample is not None: - self.__handler(sample) - - """ - " internal class __Writer - """ - class __Writer: - def __init__(self): - self.__writer = None - self.__publication_matched_count = 0 - - def Init(self, participant: DomainParticipant, topic: Topic, qos: Qos = None): - self.__writer = DataWriter(participant, topic, qos, Listener(on_publication_matched=self.__OnPublicationMatched)) - time.sleep(0.2) - - def Write(self, sample: Any, timeout: float = None): - waitsec = 0.0 if timeout is None else timeout - - # check publication_matched_count - while waitsec > 0.0 and self.__publication_matched_count == 0: - time.sleep(0.1) - waitsec = waitsec - 0.1 - # print(time.time()) - - # check waitsec - if timeout is not None and waitsec <= 0.0: - return False - - try: - self.__writer.write(sample) - except DDSException as e: - print("[Writer] catch DDSException error. msg:", e.msg) - return False - except Exception as e: - print("[Writer] write sample error. msg:", e.args()) - return False - - return True - - def Close(self): - if self.__writer is not None: - del self.__writer - - def __OnPublicationMatched(self, writer: DataWriter, status: dds_c_t.publication_matched_status): - self.__publication_matched_count = status.current_count - - - # channel __init__ - def __init__(self, participant: DomainParticipant, name: str, type: Any, qos: Qos = None): - self.__reader = self.__Reader() - self.__writer = self.__Writer() - self.__participant = participant - self.__topic = Topic(self.__participant, name, type, qos) - - def SetWriter(self, qos: Qos = None): - self.__writer.Init(self.__participant, self.__topic, qos) - - def SetReader(self, qos: Qos = None, handler: Callable = None, queueLen: int = 0): - self.__reader.Init(self.__participant, self.__topic, qos, handler, queueLen) - - def Write(self, sample: Any, timeout: float = None): - return self.__writer.Write(sample, timeout) - - def Read(self, timeout: float = None): - return self.__reader.Read(timeout) - - def CloseReader(self): - self.__reader.Close() - - def CloseWriter(self): - self.__writer.Close() - - -""" -" class ChannelFactory -""" -class ChannelFactory(Singleton): - __domain = None - __participant = None - __qos = None - - def __init__(self): - super().__init__() - - def Init(self, id: int, networkInterface: str = None, qos: Qos = None): - config = None - # choose config - if networkInterface is None: - config = ChannelConfigAutoDetermine - else: - config = ChannelConfigHasInterface.replace('$__IF_NAME__$', networkInterface) - - try: - self.__domain = Domain(id, config) - except DDSException as e: - print("[ChannelFactory] create domain error. msg:", e.msg) - return False - except: - print("[ChannelFactory] create domain error.") - return False - - try: - self.__participant = DomainParticipant(id) - except DDSException as e: - print("[ChannelFactory] create domain participant error. msg:", e.msg) - return False - except: - print("[ChannelFactory] create domain participant error") - return False - - self.__qos = qos - - return True - - def CreateChannel(self, name: str, type: Any): - return Channel(self.__participant, name, type, self.__qos) - - def CreateSendChannel(self, name: str, type: Any): - channel = self.CreateChannel(name, type) - channel.SetWriter(None) - return channel - - def CreateRecvChannel(self, name: str, type: Any, handler: Callable = None, queueLen: int = 0): - channel = self.CreateChannel(name, type) - channel.SetReader(None, handler, queueLen) - return channel - - -""" -" class ChannelPublisher -""" -class ChannelPublisher: - def __init__(self, name: str, type: Any): - factory = ChannelFactory() - self.__channel = factory.CreateChannel(name, type) - self.__inited = False - - def Init(self): - if not self.__inited: - self.__channel.SetWriter(None) - self.__inited = True - - def Close(self): - self.__channel.CloseWriter() - self.__inited = False - - def Write(self, sample: Any, timeout: float = None): - return self.__channel.Write(sample, timeout) - -""" -" class ChannelSubscriber -""" -class ChannelSubscriber: - def __init__(self, name: str, type: Any): - factory = ChannelFactory() - self.__channel = factory.CreateChannel(name, type) - self.__inited = False - - def Init(self, handler: Callable = None, queueLen: int = 0): - if not self.__inited: - self.__channel.SetReader(None, handler, queueLen) - self.__inited = True - - def Close(self): - self.__channel.CloseReader() - self.__inited = False - - def Read(self, timeout: int = None): - return self.__channel.Read(timeout) - -""" -" function ChannelFactoryInitialize. used to intialize channel everenment. -""" -def ChannelFactoryInitialize(id: int = 0, networkInterface: str = None): - factory = ChannelFactory() - if not factory.Init(id, networkInterface): - raise Exception("channel factory init error.") +import time +from typing import Any, Callable +from threading import Thread, Event + +from cyclonedds.domain import Domain, DomainParticipant +from cyclonedds.internal import dds_c_t +from cyclonedds.pub import DataWriter +from cyclonedds.sub import DataReader +from cyclonedds.topic import Topic +from cyclonedds.qos import Qos +from cyclonedds.core import DDSException, Listener +from cyclonedds.util import duration +from cyclonedds.internal import dds_c_t, InvalidSample + +# for channel config +from .channel_config import ChannelConfigAutoDetermine, ChannelConfigHasInterface + +# for singleton +from ..utils.singleton import Singleton +from ..utils.bqueue import BQueue + + +""" +" class ChannelReader +""" + +""" +" class Channel +""" +class Channel: + + """ + " internal class __Reader + """ + class __Reader: + def __init__(self): + self.__reader = None + self.__handler = None + self.__queue = None + self.__queueEnable = False + self.__threadEvent = None + self.__threadReader = None + + def Init(self, participant: DomainParticipant, topic: Topic, qos: Qos = None, handler: Callable = None, queueLen: int = 0): + if handler is None: + self.__reader = DataReader(participant, topic, qos) + else: + self.__handler = handler + if queueLen > 0: + self.__queueEnable = True + self.__queue = BQueue(queueLen) + self.__threadEvent = Event() + self.__threadReader = Thread(target=self.__ChannelReaderThreadFunc, name="ch_reader", daemon=True) + self.__threadReader.start() + self.__reader = DataReader(participant, topic, qos, Listener(on_data_available=self.__OnDataAvailable)) + + def Read(self, timeout: float = None): + sample = None + try: + if timeout is None: + sample = self.__reader.take_one() + else: + sample = self.__reader.take_one(timeout=duration(seconds=timeout)) + except DDSException as e: + print("[Reader] catch DDSException msg:", e.msg) + except TimeoutError as e: + print("[Reader] take sample timeout") + except: + print("[Reader] take sample error") + + return sample + + def Close(self): + if self.__reader is not None: + del self.__reader + + if self.__queueEnable: + self.__threadEvent.set() + self.__queue.Interrupt() + self.__queue.Clear() + self.__threadReader.join() + + def __OnDataAvailable(self, reader: DataReader): + samples = [] + try: + samples = reader.take(1) + except DDSException as e: + print("[Reader] catch DDSException error. msg:", e.msg) + return + except TimeoutError as e: + print("[Reader] take sample timeout") + return + except: + print("[Reader] take sample error") + return + + if samples is None: + return + + # check invalid sample + sample = samples[0] + if isinstance(sample, InvalidSample): + return + + # do sample + if self.__queueEnable: + self.__queue.Put(sample) + else: + self.__handler(sample) + + def __ChannelReaderThreadFunc(self): + while not self.__threadEvent.is_set(): + sample = self.__queue.Get() + if sample is not None: + self.__handler(sample) + + """ + " internal class __Writer + """ + class __Writer: + def __init__(self): + self.__writer = None + self.__publication_matched_count = 0 + + def Init(self, participant: DomainParticipant, topic: Topic, qos: Qos = None): + self.__writer = DataWriter(participant, topic, qos, Listener(on_publication_matched=self.__OnPublicationMatched)) + time.sleep(0.2) + + def Write(self, sample: Any, timeout: float = None): + waitsec = 0.0 if timeout is None else timeout + + # check publication_matched_count + while waitsec > 0.0 and self.__publication_matched_count == 0: + time.sleep(0.1) + waitsec = waitsec - 0.1 + # print(time.time()) + + # check waitsec + if timeout is not None and waitsec <= 0.0: + return False + + try: + self.__writer.write(sample) + except DDSException as e: + print("[Writer] catch DDSException error. msg:", e.msg) + return False + except Exception as e: + print("[Writer] write sample error. msg:", e.args()) + return False + + return True + + def Close(self): + if self.__writer is not None: + del self.__writer + + def __OnPublicationMatched(self, writer: DataWriter, status: dds_c_t.publication_matched_status): + self.__publication_matched_count = status.current_count + + + # channel __init__ + def __init__(self, participant: DomainParticipant, name: str, type: Any, qos: Qos = None): + self.__reader = self.__Reader() + self.__writer = self.__Writer() + self.__participant = participant + self.__topic = Topic(self.__participant, name, type, qos) + + def SetWriter(self, qos: Qos = None): + self.__writer.Init(self.__participant, self.__topic, qos) + + def SetReader(self, qos: Qos = None, handler: Callable = None, queueLen: int = 0): + self.__reader.Init(self.__participant, self.__topic, qos, handler, queueLen) + + def Write(self, sample: Any, timeout: float = None): + return self.__writer.Write(sample, timeout) + + def Read(self, timeout: float = None): + return self.__reader.Read(timeout) + + def CloseReader(self): + self.__reader.Close() + + def CloseWriter(self): + self.__writer.Close() + + +""" +" class ChannelFactory +""" +class ChannelFactory(Singleton): + __domain = None + __participant = None + __qos = None + + def __init__(self): + super().__init__() + + def Init(self, id: int, networkInterface: str = None, qos: Qos = None): + config = None + # choose config + if networkInterface is None: + config = ChannelConfigAutoDetermine + else: + config = ChannelConfigHasInterface.replace('$__IF_NAME__$', networkInterface) + + try: + self.__domain = Domain(id, config) + except DDSException as e: + print("[ChannelFactory] create domain error. msg:", e.msg) + return False + except: + print("[ChannelFactory] create domain error.") + return False + + try: + self.__participant = DomainParticipant(id) + except DDSException as e: + print("[ChannelFactory] create domain participant error. msg:", e.msg) + return False + except: + print("[ChannelFactory] create domain participant error") + return False + + self.__qos = qos + + return True + + def CreateChannel(self, name: str, type: Any): + return Channel(self.__participant, name, type, self.__qos) + + def CreateSendChannel(self, name: str, type: Any): + channel = self.CreateChannel(name, type) + channel.SetWriter(None) + return channel + + def CreateRecvChannel(self, name: str, type: Any, handler: Callable = None, queueLen: int = 0): + channel = self.CreateChannel(name, type) + channel.SetReader(None, handler, queueLen) + return channel + + +""" +" class ChannelPublisher +""" +class ChannelPublisher: + def __init__(self, name: str, type: Any): + factory = ChannelFactory() + self.__channel = factory.CreateChannel(name, type) + self.__inited = False + + def Init(self): + if not self.__inited: + self.__channel.SetWriter(None) + self.__inited = True + + def Close(self): + self.__channel.CloseWriter() + self.__inited = False + + def Write(self, sample: Any, timeout: float = None): + return self.__channel.Write(sample, timeout) + +""" +" class ChannelSubscriber +""" +class ChannelSubscriber: + def __init__(self, name: str, type: Any): + factory = ChannelFactory() + self.__channel = factory.CreateChannel(name, type) + self.__inited = False + + def Init(self, handler: Callable = None, queueLen: int = 0): + if not self.__inited: + self.__channel.SetReader(None, handler, queueLen) + self.__inited = True + + def Close(self): + self.__channel.CloseReader() + self.__inited = False + + def Read(self, timeout: int = None): + return self.__channel.Read(timeout) + +""" +" function ChannelFactoryInitialize. used to intialize channel everenment. +""" +def ChannelFactoryInitialize(id: int = 0, networkInterface: str = None): + factory = ChannelFactory() + if not factory.Init(id, networkInterface): + raise Exception("channel factory init error.") diff --git a/unitree_sdk2py/core/channel_config.py b/unitree_sdk2py/core/channel_config.py index 19a67a4..21213f5 100644 --- a/unitree_sdk2py/core/channel_config.py +++ b/unitree_sdk2py/core/channel_config.py @@ -1,25 +1,25 @@ -ChannelConfigHasInterface = ''' - - - - - - - - - config - /tmp/cdds.LOG - - - ''' - -ChannelConfigAutoDetermine = ''' - - - - - - - - - ''' +ChannelConfigHasInterface = ''' + + + + + + + + + config + /tmp/cdds.LOG + + + ''' + +ChannelConfigAutoDetermine = ''' + + + + + + + + + ''' diff --git a/unitree_sdk2py/core/channel_name.py b/unitree_sdk2py/core/channel_name.py index 722e408..8f7569c 100644 --- a/unitree_sdk2py/core/channel_name.py +++ b/unitree_sdk2py/core/channel_name.py @@ -1,34 +1,34 @@ -from enum import Enum - -""" -" Enum ChannelType -""" -class ChannelType(Enum): - SEND = 0 - RECV = 1 - -""" -" function GetClientChannelName -""" -def GetClientChannelName(serviceName: str, channelType: ChannelType): - name = "rt/api/" + serviceName - - if channelType == ChannelType.SEND: - name += "/request" - else: - name += "/response" - - return name - -""" -" function GetClientChannelName -""" -def GetServerChannelName(serviceName: str, channelType: ChannelType): - name = "rt/api/" + serviceName - - if channelType == ChannelType.SEND: - name += "/response" - else: - name += "/request" - +from enum import Enum + +""" +" Enum ChannelType +""" +class ChannelType(Enum): + SEND = 0 + RECV = 1 + +""" +" function GetClientChannelName +""" +def GetClientChannelName(serviceName: str, channelType: ChannelType): + name = "rt/api/" + serviceName + + if channelType == ChannelType.SEND: + name += "/request" + else: + name += "/response" + + return name + +""" +" function GetClientChannelName +""" +def GetServerChannelName(serviceName: str, channelType: ChannelType): + name = "rt/api/" + serviceName + + if channelType == ChannelType.SEND: + name += "/response" + else: + name += "/request" + return name \ No newline at end of file diff --git a/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_api.py b/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_api.py index af0a50d..bab43c3 100644 --- a/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_api.py +++ b/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_api.py @@ -1,17 +1,17 @@ -""" -" service name -""" -OBSTACLES_AVOID_SERVICE_NAME = "obstacles_avoid" - - -""" -" service api version -""" -OBSTACLES_AVOID_API_VERSION = "1.0.0.1" - - -""" -" api id -""" -OBSTACLES_AVOID_API_ID_SWITCH_SET = 1001 -OBSTACLES_AVOID_API_ID_SWITCH_GET = 1002 +""" +" service name +""" +OBSTACLES_AVOID_SERVICE_NAME = "obstacles_avoid" + + +""" +" service api version +""" +OBSTACLES_AVOID_API_VERSION = "1.0.0.1" + + +""" +" api id +""" +OBSTACLES_AVOID_API_ID_SWITCH_SET = 1001 +OBSTACLES_AVOID_API_ID_SWITCH_GET = 1002 diff --git a/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_client.py b/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_client.py index d17dfda..f66d822 100644 --- a/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_client.py +++ b/unitree_sdk2py/go2/obstacles_avoid/obstacles_avoid_client.py @@ -1,40 +1,40 @@ -import json - -from ...rpc.client import Client -from .obstacles_avoid_api import * - - -""" -" class ObstaclesAvoidClient -""" -class ObstaclesAvoidClient(Client): - def __init__(self): - super().__init__(OBSTACLES_AVOID_SERVICE_NAME, False) - - def Init(self): - # set api version - self._SetApiVerson(OBSTACLES_AVOID_API_VERSION) - # regist api - self._RegistApi(OBSTACLES_AVOID_API_ID_SWITCH_SET, 0) - self._RegistApi(OBSTACLES_AVOID_API_ID_SWITCH_GET, 0) - - # 1001 - def SwitchSet(self, on: bool): - p = {} - p["enable"] = on - parameter = json.dumps(p) - - code, data = self._Call(OBSTACLES_AVOID_API_ID_SWITCH_SET, parameter) - return code - - # 1002 - def SwitchGet(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(OBSTACLES_AVOID_API_ID_SWITCH_GET, parameter) - if code == 0: - d = json.loads(data) - return code, d["enable"] - else: +import json + +from ...rpc.client import Client +from .obstacles_avoid_api import * + + +""" +" class ObstaclesAvoidClient +""" +class ObstaclesAvoidClient(Client): + def __init__(self): + super().__init__(OBSTACLES_AVOID_SERVICE_NAME, False) + + def Init(self): + # set api version + self._SetApiVerson(OBSTACLES_AVOID_API_VERSION) + # regist api + self._RegistApi(OBSTACLES_AVOID_API_ID_SWITCH_SET, 0) + self._RegistApi(OBSTACLES_AVOID_API_ID_SWITCH_GET, 0) + + # 1001 + def SwitchSet(self, on: bool): + p = {} + p["enable"] = on + parameter = json.dumps(p) + + code, data = self._Call(OBSTACLES_AVOID_API_ID_SWITCH_SET, parameter) + return code + + # 1002 + def SwitchGet(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(OBSTACLES_AVOID_API_ID_SWITCH_GET, parameter) + if code == 0: + d = json.loads(data) + return code, d["enable"] + else: return code, None \ No newline at end of file diff --git a/unitree_sdk2py/go2/robot_state/robot_state_api.py b/unitree_sdk2py/go2/robot_state/robot_state_api.py index fde54df..b8cc869 100644 --- a/unitree_sdk2py/go2/robot_state/robot_state_api.py +++ b/unitree_sdk2py/go2/robot_state/robot_state_api.py @@ -1,25 +1,25 @@ -""" -" service name -""" -ROBOT_STATE_SERVICE_NAME = "robot_state" - - -""" -" service api version -""" -ROBOT_STATE_API_VERSION = "1.0.0.1" - - -""" -" api id -""" -ROBOT_STATE_API_ID_SERVICE_SWITCH = 1001 -ROBOT_STATE_API_ID_REPORT_FREQ = 1002 -ROBOT_STATE_API_ID_SERVICE_LIST = 1003 - - -""" -" error code -""" -ROBOT_STATE_ERR_SERVICE_SWITCH = 5201 -ROBOT_STATE_ERR_SERVICE_PROTECTED = 5202 +""" +" service name +""" +ROBOT_STATE_SERVICE_NAME = "robot_state" + + +""" +" service api version +""" +ROBOT_STATE_API_VERSION = "1.0.0.1" + + +""" +" api id +""" +ROBOT_STATE_API_ID_SERVICE_SWITCH = 1001 +ROBOT_STATE_API_ID_REPORT_FREQ = 1002 +ROBOT_STATE_API_ID_SERVICE_LIST = 1003 + + +""" +" error code +""" +ROBOT_STATE_ERR_SERVICE_SWITCH = 5201 +ROBOT_STATE_ERR_SERVICE_PROTECTED = 5202 diff --git a/unitree_sdk2py/go2/robot_state/robot_state_client.py b/unitree_sdk2py/go2/robot_state/robot_state_client.py index 5b2e74d..1e1d3a9 100644 --- a/unitree_sdk2py/go2/robot_state/robot_state_client.py +++ b/unitree_sdk2py/go2/robot_state/robot_state_client.py @@ -1,84 +1,84 @@ -import json - -from ...rpc.client import Client -from ...rpc.client_internal import * -from .robot_state_api import * - - -""" -" class ServiceState -""" -class ServiceState: - def __init__(self, name: str = None, status: int = None, protect: bool = None): - self.name = name - self.status = status - self.protect = protect - -""" -" class RobotStateClient -""" -class RobotStateClient(Client): - def __init__(self): - super().__init__(ROBOT_STATE_SERVICE_NAME, False) - - def Init(self): - # set api version - self._SetApiVerson(ROBOT_STATE_API_VERSION) - # regist api - self._RegistApi(ROBOT_STATE_API_ID_SERVICE_SWITCH, 0) - self._RegistApi(ROBOT_STATE_API_ID_REPORT_FREQ, 0) - self._RegistApi(ROBOT_STATE_API_ID_SERVICE_LIST, 0) - - def ServiceList(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(ROBOT_STATE_API_ID_SERVICE_LIST, parameter) - - if code != 0: - return code, None - - lst = [] - - d = json.loads(data) - for t in d: - s = ServiceState() - s.name = t["name"] - s.status = t["status"] - s.protect = t["protect"] - lst.append(s) - - return code, lst - - - def ServiceSwitch(self, name: str, switch: bool): - p = {} - p["name"] = name - p["switch"] = int(switch) - parameter = json.dumps(p) - - code, data = self._Call(ROBOT_STATE_API_ID_SERVICE_SWITCH, parameter) - - if code != 0: - return code - - d = json.loads(data) - - status = d["status"] - - if status == 5: - return ROBOT_STATE_ERR_SERVICE_PROTECTED - - if status != 0 and status != 1: - return ROBOT_STATE_ERR_SERVICE_SWITCH - - return code - - def SetReportFreq(self, interval: int, duration: int): - p = {} - p["interval"] = interval - p["duration"] = duration - parameter = json.dumps(p) - - code, data = self._Call(ROBOT_STATE_API_ID_REPORT_FREQ, p) - return code +import json + +from ...rpc.client import Client +from ...rpc.client_internal import * +from .robot_state_api import * + + +""" +" class ServiceState +""" +class ServiceState: + def __init__(self, name: str = None, status: int = None, protect: bool = None): + self.name = name + self.status = status + self.protect = protect + +""" +" class RobotStateClient +""" +class RobotStateClient(Client): + def __init__(self): + super().__init__(ROBOT_STATE_SERVICE_NAME, False) + + def Init(self): + # set api version + self._SetApiVerson(ROBOT_STATE_API_VERSION) + # regist api + self._RegistApi(ROBOT_STATE_API_ID_SERVICE_SWITCH, 0) + self._RegistApi(ROBOT_STATE_API_ID_REPORT_FREQ, 0) + self._RegistApi(ROBOT_STATE_API_ID_SERVICE_LIST, 0) + + def ServiceList(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(ROBOT_STATE_API_ID_SERVICE_LIST, parameter) + + if code != 0: + return code, None + + lst = [] + + d = json.loads(data) + for t in d: + s = ServiceState() + s.name = t["name"] + s.status = t["status"] + s.protect = t["protect"] + lst.append(s) + + return code, lst + + + def ServiceSwitch(self, name: str, switch: bool): + p = {} + p["name"] = name + p["switch"] = int(switch) + parameter = json.dumps(p) + + code, data = self._Call(ROBOT_STATE_API_ID_SERVICE_SWITCH, parameter) + + if code != 0: + return code + + d = json.loads(data) + + status = d["status"] + + if status == 5: + return ROBOT_STATE_ERR_SERVICE_PROTECTED + + if status != 0 and status != 1: + return ROBOT_STATE_ERR_SERVICE_SWITCH + + return code + + def SetReportFreq(self, interval: int, duration: int): + p = {} + p["interval"] = interval + p["duration"] = duration + parameter = json.dumps(p) + + code, data = self._Call(ROBOT_STATE_API_ID_REPORT_FREQ, p) + return code diff --git a/unitree_sdk2py/go2/sport/sport_api.py b/unitree_sdk2py/go2/sport/sport_api.py index c399031..c9d175d 100644 --- a/unitree_sdk2py/go2/sport/sport_api.py +++ b/unitree_sdk2py/go2/sport/sport_api.py @@ -1,61 +1,61 @@ -""" -" service name -""" -SPORT_SERVICE_NAME = "sport" - - -""" -" service api version -""" -SPORT_API_VERSION = "1.0.0.1" - - -""" -" api id -""" -SPORT_API_ID_DAMP = 1001 -SPORT_API_ID_BALANCESTAND = 1002 -SPORT_API_ID_STOPMOVE = 1003 -SPORT_API_ID_STANDUP = 1004 -SPORT_API_ID_STANDDOWN = 1005 -SPORT_API_ID_RECOVERYSTAND = 1006 -SPORT_API_ID_EULER = 1007 -SPORT_API_ID_MOVE = 1008 -SPORT_API_ID_SIT = 1009 -SPORT_API_ID_RISESIT = 1010 -SPORT_API_ID_SWITCHGAIT = 1011 -SPORT_API_ID_TRIGGER = 1012 -SPORT_API_ID_BODYHEIGHT = 1013 -SPORT_API_ID_FOOTRAISEHEIGHT = 1014 -SPORT_API_ID_SPEEDLEVEL = 1015 -SPORT_API_ID_HELLO = 1016 -SPORT_API_ID_STRETCH = 1017 -SPORT_API_ID_TRAJECTORYFOLLOW = 1018 -SPORT_API_ID_CONTINUOUSGAIT = 1019 -SPORT_API_ID_CONTENT = 1020 -SPORT_API_ID_WALLOW = 1021 -SPORT_API_ID_DANCE1 = 1022 -SPORT_API_ID_DANCE2 = 1023 -SPORT_API_ID_GETBODYHEIGHT = 1024 -SPORT_API_ID_GETFOOTRAISEHEIGHT = 1025 -SPORT_API_ID_GETSPEEDLEVEL = 1026 -SPORT_API_ID_SWITCHJOYSTICK = 1027 -SPORT_API_ID_POSE = 1028 -SPORT_API_ID_SCRAPE = 1029 -SPORT_API_ID_FRONTFLIP = 1030 -SPORT_API_ID_FRONTJUMP = 1031 -SPORT_API_ID_FRONTPOUNCE = 1032 -SPORT_API_ID_WIGGLEHIPS = 1033 -SPORT_API_ID_GETSTATE = 1034 -SPORT_API_ID_ECONOMICGAIT = 1035 -SPORT_API_ID_HEART = 1036 - - -""" -" error code -""" -# client side -SPORT_ERR_CLIENT_POINT_PATH = 4101 -# server side -SPORT_ERR_SERVER_OVERTIME = 4201 -SPORT_ERR_SERVER_NOT_INIT = 4202 +""" +" service name +""" +SPORT_SERVICE_NAME = "sport" + + +""" +" service api version +""" +SPORT_API_VERSION = "1.0.0.1" + + +""" +" api id +""" +SPORT_API_ID_DAMP = 1001 +SPORT_API_ID_BALANCESTAND = 1002 +SPORT_API_ID_STOPMOVE = 1003 +SPORT_API_ID_STANDUP = 1004 +SPORT_API_ID_STANDDOWN = 1005 +SPORT_API_ID_RECOVERYSTAND = 1006 +SPORT_API_ID_EULER = 1007 +SPORT_API_ID_MOVE = 1008 +SPORT_API_ID_SIT = 1009 +SPORT_API_ID_RISESIT = 1010 +SPORT_API_ID_SWITCHGAIT = 1011 +SPORT_API_ID_TRIGGER = 1012 +SPORT_API_ID_BODYHEIGHT = 1013 +SPORT_API_ID_FOOTRAISEHEIGHT = 1014 +SPORT_API_ID_SPEEDLEVEL = 1015 +SPORT_API_ID_HELLO = 1016 +SPORT_API_ID_STRETCH = 1017 +SPORT_API_ID_TRAJECTORYFOLLOW = 1018 +SPORT_API_ID_CONTINUOUSGAIT = 1019 +SPORT_API_ID_CONTENT = 1020 +SPORT_API_ID_WALLOW = 1021 +SPORT_API_ID_DANCE1 = 1022 +SPORT_API_ID_DANCE2 = 1023 +SPORT_API_ID_GETBODYHEIGHT = 1024 +SPORT_API_ID_GETFOOTRAISEHEIGHT = 1025 +SPORT_API_ID_GETSPEEDLEVEL = 1026 +SPORT_API_ID_SWITCHJOYSTICK = 1027 +SPORT_API_ID_POSE = 1028 +SPORT_API_ID_SCRAPE = 1029 +SPORT_API_ID_FRONTFLIP = 1030 +SPORT_API_ID_FRONTJUMP = 1031 +SPORT_API_ID_FRONTPOUNCE = 1032 +SPORT_API_ID_WIGGLEHIPS = 1033 +SPORT_API_ID_GETSTATE = 1034 +SPORT_API_ID_ECONOMICGAIT = 1035 +SPORT_API_ID_HEART = 1036 + + +""" +" error code +""" +# client side +SPORT_ERR_CLIENT_POINT_PATH = 4101 +# server side +SPORT_ERR_SERVER_OVERTIME = 4201 +SPORT_ERR_SERVER_NOT_INIT = 4202 diff --git a/unitree_sdk2py/go2/sport/sport_client.py b/unitree_sdk2py/go2/sport/sport_client.py index 8fea8b8..87f5148 100644 --- a/unitree_sdk2py/go2/sport/sport_client.py +++ b/unitree_sdk2py/go2/sport/sport_client.py @@ -1,364 +1,364 @@ -import json - -from ...rpc.client import Client -from .sport_api import * - -""" -" SPORT_PATH_POINT_SIZE -""" -SPORT_PATH_POINT_SIZE = 30 - - -""" -" class PathPoint -""" -class PathPoint: - def __init__(self, timeFromStart: float, x: float, y: float, yaw: float, vx: float, vy: float, vyaw: float): - self.timeFromStart = timeFromStart - self.x = x - self.y = y - self.yaw = yaw - self.vx = vx - self.vy = vy - self.vyaw = vyaw - - -""" -" class SportClient -""" -class SportClient(Client): - def __init__(self, enableLease: bool = False): - super().__init__(SPORT_SERVICE_NAME, enableLease) - - - def Init(self): - # set api version - self._SetApiVerson(SPORT_API_VERSION) - - # regist api - self._RegistApi(SPORT_API_ID_DAMP, 0) - self._RegistApi(SPORT_API_ID_BALANCESTAND, 0) - self._RegistApi(SPORT_API_ID_STOPMOVE, 0) - self._RegistApi(SPORT_API_ID_STANDUP, 0) - self._RegistApi(SPORT_API_ID_STANDDOWN, 0) - self._RegistApi(SPORT_API_ID_RECOVERYSTAND, 0) - self._RegistApi(SPORT_API_ID_EULER, 0) - self._RegistApi(SPORT_API_ID_MOVE, 0) - self._RegistApi(SPORT_API_ID_SIT, 0) - self._RegistApi(SPORT_API_ID_RISESIT, 0) - self._RegistApi(SPORT_API_ID_SWITCHGAIT, 0) - self._RegistApi(SPORT_API_ID_TRIGGER, 0) - self._RegistApi(SPORT_API_ID_BODYHEIGHT, 0) - self._RegistApi(SPORT_API_ID_FOOTRAISEHEIGHT, 0) - self._RegistApi(SPORT_API_ID_SPEEDLEVEL, 0) - self._RegistApi(SPORT_API_ID_HELLO, 0) - self._RegistApi(SPORT_API_ID_STRETCH, 0) - self._RegistApi(SPORT_API_ID_TRAJECTORYFOLLOW, 0) - self._RegistApi(SPORT_API_ID_CONTINUOUSGAIT, 0) - # self._RegistApi(SPORT_API_ID_CONTENT, 0) - self._RegistApi(SPORT_API_ID_WALLOW, 0) - self._RegistApi(SPORT_API_ID_DANCE1, 0) - self._RegistApi(SPORT_API_ID_DANCE2, 0) - # self._RegistApi(SPORT_API_ID_GETBODYHEIGHT, 0) - # self._RegistApi(SPORT_API_ID_GETFOOTRAISEHEIGHT, 0) - # self._RegistApi(SPORT_API_ID_GETSPEEDLEVEL, 0) - self._RegistApi(SPORT_API_ID_SWITCHJOYSTICK, 0) - self._RegistApi(SPORT_API_ID_POSE, 0) - self._RegistApi(SPORT_API_ID_SCRAPE, 0) - self._RegistApi(SPORT_API_ID_FRONTFLIP, 0) - self._RegistApi(SPORT_API_ID_FRONTJUMP, 0) - self._RegistApi(SPORT_API_ID_FRONTPOUNCE, 0) - self._RegistApi(SPORT_API_ID_WIGGLEHIPS, 0) - self._RegistApi(SPORT_API_ID_GETSTATE, 0) - self._RegistApi(SPORT_API_ID_ECONOMICGAIT, 0) - self._RegistApi(SPORT_API_ID_HEART, 0) - - # 1001 - def Damp(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_DAMP, parameter) - return code - - # 1002 - def BalanceStand(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_BALANCESTAND, parameter) - return code - - # 1003 - def StopMove(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_STOPMOVE, parameter) - return code - - # 1004 - def StandUp(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_STANDUP, parameter) - return code - - # 1005 - def StandDown(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_STANDDOWN, parameter) - return code - - # 1006 - def RecoveryStand(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_RECOVERYSTAND, parameter) - return code - - # 1007 - def Euler(self, roll: float, pitch: float, yaw: float): - p = {} - p["x"] = roll - p["y"] = pitch - p["z"] = yaw - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_EULER, parameter) - return code - - # 1008 - def Move(self, vx: float, vy: float, vyaw: float): - p = {} - p["x"] = vx - p["y"] = vy - p["z"] = vyaw - parameter = json.dumps(p) - code = self._CallNoReply(SPORT_API_ID_MOVE, parameter) - return code - - # 1009 - def Sit(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_SIT, parameter) - return code - - #1010 - def RiseSit(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_RISESIT, parameter) - return code - - # 1011 - def SwitchGait(self, t: int): - p = {} - p["data"] = t - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_SWITCHGAIT, parameter) - return code - - # 1012 - def Trigger(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_TRIGGER, parameter) - return code - - # 1013 - def BodyHeight(self, height: float): - p = {} - p["data"] = height - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_BODYHEIGHT, parameter) - return code - - # 1014 - def FootRaiseHeight(self, height: float): - p = {} - p["data"] = height - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_FOOTRAISEHEIGHT, parameter) - return code - - # 1015 - def SpeedLevel(self, level: int): - p = {} - p["data"] = level - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_SPEEDLEVEL, parameter) - return code - - # 1016 - def Hello(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_HELLO, parameter) - return code - - # 1017 - def Stretch(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_STRETCH, parameter) - return code - - # 1018 - def TrajectoryFollow(self, path: list): - l = len(path) - if l != SPORT_PATH_POINT_SIZE: - return SPORT_ERR_CLIENT_POINT_PATH - - path_p = [] - for i in range(l): - point = path[i] - p = {} - p["t_from_start"] = point.timeFromStart - p["x"] = point.x - p["y"] = point.y - p["yaw"] = point.yaw - p["vx"] = point.vx - p["vy"] = point.vy - p["vyaw"] = point.vyaw - path_p.append(p) - - parameter = json.dumps(path_p) - code = self._CallNoReply(SPORT_API_ID_TRAJECTORYFOLLOW, parameter) - return code - - # 1019 - def ContinuousGait(self, flag: int): - p = {} - p["data"] = flag - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_CONTINUOUSGAIT, parameter) - return code - - # # 1020 - # def Content(self): - # p = {} - # parameter = json.dumps(p) - # code, data = self._Call(SPORT_API_ID_CONTENT, parameter) - # return code - - # 1021 - def Wallow(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_WALLOW, parameter) - return code - - # 1022 - def Dance1(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_DANCE1, parameter) - return code - - # 1023 - def Dance2(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_DANCE2, parameter) - return code - - # 1025 - def GetFootRaiseHeight(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(SPORT_API_ID_GETFOOTRAISEHEIGHT, parameter) - - if code == 0: - d = json.loads(data) - return code, d["data"] - else: - return code, None - - - # 1026 - def GetSpeedLevel(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(SPORT_API_ID_GETSPEEDLEVEL, parameter) - - if code == 0: - d = json.loads(data) - return code, d["data"] - else: - return code, None - - # 1027 - def SwitchJoystick(self, on: bool): - p = {} - p["data"] = on - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_SWITCHJOYSTICK, parameter) - return code - - # 1028 - def Pose(self, flag: bool): - p = {} - p["data"] = flag - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_POSE, parameter) - return code - - # 1029 - def Scrape(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_SCRAPE, parameter) - return code - - # 1030 - def FrontFlip(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_FRONTFLIP, parameter) - return code - - # 1031 - def FrontJump(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_FRONTJUMP, parameter) - return code - - # 1032 - def FrontPounce(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_FRONTPOUNCE, parameter) - return code - - # 1033 - def WiggleHips(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_WIGGLEHIPS, parameter) - return code - - # 1034 - def GetState(self, keys: list): - parameter = json.dumps(keys) - code, data = self._Call(SPORT_API_ID_GETSTATE, parameter) - if code == 0: - return code, json.loads(data) - else: - return code, None - - # 1035 - def EconomicGait(self, flag: bool): - p = {} - p["data"] = flag - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_ECONOMICGAIT, parameter) - return code - - # 1036 - def Heart(self): - p = {} - parameter = json.dumps(p) - code, data = self._Call(SPORT_API_ID_HEART, parameter) +import json + +from ...rpc.client import Client +from .sport_api import * + +""" +" SPORT_PATH_POINT_SIZE +""" +SPORT_PATH_POINT_SIZE = 30 + + +""" +" class PathPoint +""" +class PathPoint: + def __init__(self, timeFromStart: float, x: float, y: float, yaw: float, vx: float, vy: float, vyaw: float): + self.timeFromStart = timeFromStart + self.x = x + self.y = y + self.yaw = yaw + self.vx = vx + self.vy = vy + self.vyaw = vyaw + + +""" +" class SportClient +""" +class SportClient(Client): + def __init__(self, enableLease: bool = False): + super().__init__(SPORT_SERVICE_NAME, enableLease) + + + def Init(self): + # set api version + self._SetApiVerson(SPORT_API_VERSION) + + # regist api + self._RegistApi(SPORT_API_ID_DAMP, 0) + self._RegistApi(SPORT_API_ID_BALANCESTAND, 0) + self._RegistApi(SPORT_API_ID_STOPMOVE, 0) + self._RegistApi(SPORT_API_ID_STANDUP, 0) + self._RegistApi(SPORT_API_ID_STANDDOWN, 0) + self._RegistApi(SPORT_API_ID_RECOVERYSTAND, 0) + self._RegistApi(SPORT_API_ID_EULER, 0) + self._RegistApi(SPORT_API_ID_MOVE, 0) + self._RegistApi(SPORT_API_ID_SIT, 0) + self._RegistApi(SPORT_API_ID_RISESIT, 0) + self._RegistApi(SPORT_API_ID_SWITCHGAIT, 0) + self._RegistApi(SPORT_API_ID_TRIGGER, 0) + self._RegistApi(SPORT_API_ID_BODYHEIGHT, 0) + self._RegistApi(SPORT_API_ID_FOOTRAISEHEIGHT, 0) + self._RegistApi(SPORT_API_ID_SPEEDLEVEL, 0) + self._RegistApi(SPORT_API_ID_HELLO, 0) + self._RegistApi(SPORT_API_ID_STRETCH, 0) + self._RegistApi(SPORT_API_ID_TRAJECTORYFOLLOW, 0) + self._RegistApi(SPORT_API_ID_CONTINUOUSGAIT, 0) + # self._RegistApi(SPORT_API_ID_CONTENT, 0) + self._RegistApi(SPORT_API_ID_WALLOW, 0) + self._RegistApi(SPORT_API_ID_DANCE1, 0) + self._RegistApi(SPORT_API_ID_DANCE2, 0) + # self._RegistApi(SPORT_API_ID_GETBODYHEIGHT, 0) + # self._RegistApi(SPORT_API_ID_GETFOOTRAISEHEIGHT, 0) + # self._RegistApi(SPORT_API_ID_GETSPEEDLEVEL, 0) + self._RegistApi(SPORT_API_ID_SWITCHJOYSTICK, 0) + self._RegistApi(SPORT_API_ID_POSE, 0) + self._RegistApi(SPORT_API_ID_SCRAPE, 0) + self._RegistApi(SPORT_API_ID_FRONTFLIP, 0) + self._RegistApi(SPORT_API_ID_FRONTJUMP, 0) + self._RegistApi(SPORT_API_ID_FRONTPOUNCE, 0) + self._RegistApi(SPORT_API_ID_WIGGLEHIPS, 0) + self._RegistApi(SPORT_API_ID_GETSTATE, 0) + self._RegistApi(SPORT_API_ID_ECONOMICGAIT, 0) + self._RegistApi(SPORT_API_ID_HEART, 0) + + # 1001 + def Damp(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_DAMP, parameter) + return code + + # 1002 + def BalanceStand(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_BALANCESTAND, parameter) + return code + + # 1003 + def StopMove(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_STOPMOVE, parameter) + return code + + # 1004 + def StandUp(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_STANDUP, parameter) + return code + + # 1005 + def StandDown(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_STANDDOWN, parameter) + return code + + # 1006 + def RecoveryStand(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_RECOVERYSTAND, parameter) + return code + + # 1007 + def Euler(self, roll: float, pitch: float, yaw: float): + p = {} + p["x"] = roll + p["y"] = pitch + p["z"] = yaw + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_EULER, parameter) + return code + + # 1008 + def Move(self, vx: float, vy: float, vyaw: float): + p = {} + p["x"] = vx + p["y"] = vy + p["z"] = vyaw + parameter = json.dumps(p) + code = self._CallNoReply(SPORT_API_ID_MOVE, parameter) + return code + + # 1009 + def Sit(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_SIT, parameter) + return code + + #1010 + def RiseSit(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_RISESIT, parameter) + return code + + # 1011 + def SwitchGait(self, t: int): + p = {} + p["data"] = t + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_SWITCHGAIT, parameter) + return code + + # 1012 + def Trigger(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_TRIGGER, parameter) + return code + + # 1013 + def BodyHeight(self, height: float): + p = {} + p["data"] = height + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_BODYHEIGHT, parameter) + return code + + # 1014 + def FootRaiseHeight(self, height: float): + p = {} + p["data"] = height + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_FOOTRAISEHEIGHT, parameter) + return code + + # 1015 + def SpeedLevel(self, level: int): + p = {} + p["data"] = level + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_SPEEDLEVEL, parameter) + return code + + # 1016 + def Hello(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_HELLO, parameter) + return code + + # 1017 + def Stretch(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_STRETCH, parameter) + return code + + # 1018 + def TrajectoryFollow(self, path: list): + l = len(path) + if l != SPORT_PATH_POINT_SIZE: + return SPORT_ERR_CLIENT_POINT_PATH + + path_p = [] + for i in range(l): + point = path[i] + p = {} + p["t_from_start"] = point.timeFromStart + p["x"] = point.x + p["y"] = point.y + p["yaw"] = point.yaw + p["vx"] = point.vx + p["vy"] = point.vy + p["vyaw"] = point.vyaw + path_p.append(p) + + parameter = json.dumps(path_p) + code = self._CallNoReply(SPORT_API_ID_TRAJECTORYFOLLOW, parameter) + return code + + # 1019 + def ContinuousGait(self, flag: int): + p = {} + p["data"] = flag + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_CONTINUOUSGAIT, parameter) + return code + + # # 1020 + # def Content(self): + # p = {} + # parameter = json.dumps(p) + # code, data = self._Call(SPORT_API_ID_CONTENT, parameter) + # return code + + # 1021 + def Wallow(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_WALLOW, parameter) + return code + + # 1022 + def Dance1(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_DANCE1, parameter) + return code + + # 1023 + def Dance2(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_DANCE2, parameter) + return code + + # 1025 + def GetFootRaiseHeight(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(SPORT_API_ID_GETFOOTRAISEHEIGHT, parameter) + + if code == 0: + d = json.loads(data) + return code, d["data"] + else: + return code, None + + + # 1026 + def GetSpeedLevel(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(SPORT_API_ID_GETSPEEDLEVEL, parameter) + + if code == 0: + d = json.loads(data) + return code, d["data"] + else: + return code, None + + # 1027 + def SwitchJoystick(self, on: bool): + p = {} + p["data"] = on + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_SWITCHJOYSTICK, parameter) + return code + + # 1028 + def Pose(self, flag: bool): + p = {} + p["data"] = flag + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_POSE, parameter) + return code + + # 1029 + def Scrape(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_SCRAPE, parameter) + return code + + # 1030 + def FrontFlip(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_FRONTFLIP, parameter) + return code + + # 1031 + def FrontJump(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_FRONTJUMP, parameter) + return code + + # 1032 + def FrontPounce(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_FRONTPOUNCE, parameter) + return code + + # 1033 + def WiggleHips(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_WIGGLEHIPS, parameter) + return code + + # 1034 + def GetState(self, keys: list): + parameter = json.dumps(keys) + code, data = self._Call(SPORT_API_ID_GETSTATE, parameter) + if code == 0: + return code, json.loads(data) + else: + return code, None + + # 1035 + def EconomicGait(self, flag: bool): + p = {} + p["data"] = flag + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_ECONOMICGAIT, parameter) + return code + + # 1036 + def Heart(self): + p = {} + parameter = json.dumps(p) + code, data = self._Call(SPORT_API_ID_HEART, parameter) return code \ No newline at end of file diff --git a/unitree_sdk2py/go2/video/video_api.py b/unitree_sdk2py/go2/video/video_api.py index a4cb1b6..734de20 100644 --- a/unitree_sdk2py/go2/video/video_api.py +++ b/unitree_sdk2py/go2/video/video_api.py @@ -1,16 +1,16 @@ -""" -" service name -""" -VIDEO_SERVICE_NAME = "videohub" - - -""" -" service api version -""" -VIDEO_API_VERSION = "1.0.0.1" - - -""" -" api id -""" -VIDEO_API_ID_GETIMAGESAMPLE = 1001 +""" +" service name +""" +VIDEO_SERVICE_NAME = "videohub" + + +""" +" service api version +""" +VIDEO_API_VERSION = "1.0.0.1" + + +""" +" api id +""" +VIDEO_API_ID_GETIMAGESAMPLE = 1001 diff --git a/unitree_sdk2py/go2/video/video_client.py b/unitree_sdk2py/go2/video/video_client.py index 79e1fb5..9d9aedc 100644 --- a/unitree_sdk2py/go2/video/video_client.py +++ b/unitree_sdk2py/go2/video/video_client.py @@ -1,23 +1,23 @@ -import json - -from ...rpc.client import Client -from .video_api import * - - -""" -" class VideoClient -""" -class VideoClient(Client): - def __init__(self): - super().__init__(VIDEO_SERVICE_NAME, False) - - - def Init(self): - # set api version - self._SetApiVerson(VIDEO_API_VERSION) - # regist api - self._RegistApi(VIDEO_API_ID_GETIMAGESAMPLE, 0) - - # 1001 - def GetImageSample(self): - return self._CallBinary(VIDEO_API_ID_GETIMAGESAMPLE, []) +import json + +from ...rpc.client import Client +from .video_api import * + + +""" +" class VideoClient +""" +class VideoClient(Client): + def __init__(self): + super().__init__(VIDEO_SERVICE_NAME, False) + + + def Init(self): + # set api version + self._SetApiVerson(VIDEO_API_VERSION) + # regist api + self._RegistApi(VIDEO_API_ID_GETIMAGESAMPLE, 0) + + # 1001 + def GetImageSample(self): + return self._CallBinary(VIDEO_API_ID_GETIMAGESAMPLE, []) diff --git a/unitree_sdk2py/go2/vui/vui_api.py b/unitree_sdk2py/go2/vui/vui_api.py index d5dcd34..abeeb81 100644 --- a/unitree_sdk2py/go2/vui/vui_api.py +++ b/unitree_sdk2py/go2/vui/vui_api.py @@ -1,21 +1,21 @@ -""" -" service name -""" -VUI_SERVICE_NAME = "vui" - - -""" -" service api version -""" -VUI_API_VERSION = "1.0.0.1" - - -""" -" api id -""" -VUI_API_ID_SETSWITCH = 1001 -VUI_API_ID_GETSWITCH = 1002 -VUI_API_ID_SETVOLUME = 1003 -VUI_API_ID_GETVOLUME = 1004 -VUI_API_ID_SETBRIGHTNESS = 1005 -VUI_API_ID_GETBRIGHTNESS = 1006 +""" +" service name +""" +VUI_SERVICE_NAME = "vui" + + +""" +" service api version +""" +VUI_API_VERSION = "1.0.0.1" + + +""" +" api id +""" +VUI_API_ID_SETSWITCH = 1001 +VUI_API_ID_GETSWITCH = 1002 +VUI_API_ID_SETVOLUME = 1003 +VUI_API_ID_GETVOLUME = 1004 +VUI_API_ID_SETBRIGHTNESS = 1005 +VUI_API_ID_GETBRIGHTNESS = 1006 diff --git a/unitree_sdk2py/go2/vui/vui_client.py b/unitree_sdk2py/go2/vui/vui_client.py index 234f285..b523c3b 100644 --- a/unitree_sdk2py/go2/vui/vui_client.py +++ b/unitree_sdk2py/go2/vui/vui_client.py @@ -1,86 +1,86 @@ -import json - -from ...rpc.client import Client -from .vui_api import * - - -""" -" class VideoClient -""" -class VuiClient(Client): - def __init__(self): - super().__init__(VUI_SERVICE_NAME, False) - - def Init(self): - # set api version - self._SetApiVerson(VUI_API_VERSION) - # regist api - self._RegistApi(VUI_API_ID_SETSWITCH, 0) - self._RegistApi(VUI_API_ID_GETSWITCH, 0) - self._RegistApi(VUI_API_ID_SETVOLUME, 0) - self._RegistApi(VUI_API_ID_GETVOLUME, 0) - self._RegistApi(VUI_API_ID_SETBRIGHTNESS, 0) - self._RegistApi(VUI_API_ID_GETBRIGHTNESS, 0) - - # 1001 - def SetSwitch(self, enable: int): - p = {} - p["enable"] = enable - parameter = json.dumps(p) - - code, data = self._Call(VUI_API_ID_SETSWITCH, parameter) - return code - - # 1002 - def GetSwitch(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(VUI_API_ID_GETSWITCH, parameter) - if code == 0: - d = json.loads(data) - return code, d["enable"] - else: - return code, None - - # 1003 - def SetVolume(self, level: int): - p = {} - p["volume"] = level - parameter = json.dumps(p) - - code, data = self._Call(VUI_API_ID_SETVOLUME, parameter) - return code - - # 1006 - def GetVolume(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(VUI_API_ID_GETVOLUME, parameter) - if code == 0: - d = json.loads(data) - return code, d["volume"] - else: - return code, None - - # 1005 - def SetBrightness(self, level: int): - p = {} - p["brightness"] = level - parameter = json.dumps(p) - - code, data = self._Call(VUI_API_ID_SETBRIGHTNESS, parameter) - return code - - # 1006 - def GetBrightness(self): - p = {} - parameter = json.dumps(p) - - code, data = self._Call(VUI_API_ID_GETBRIGHTNESS, parameter) - if code == 0: - d = json.loads(data) - return code, d["brightness"] - else: +import json + +from ...rpc.client import Client +from .vui_api import * + + +""" +" class VideoClient +""" +class VuiClient(Client): + def __init__(self): + super().__init__(VUI_SERVICE_NAME, False) + + def Init(self): + # set api version + self._SetApiVerson(VUI_API_VERSION) + # regist api + self._RegistApi(VUI_API_ID_SETSWITCH, 0) + self._RegistApi(VUI_API_ID_GETSWITCH, 0) + self._RegistApi(VUI_API_ID_SETVOLUME, 0) + self._RegistApi(VUI_API_ID_GETVOLUME, 0) + self._RegistApi(VUI_API_ID_SETBRIGHTNESS, 0) + self._RegistApi(VUI_API_ID_GETBRIGHTNESS, 0) + + # 1001 + def SetSwitch(self, enable: int): + p = {} + p["enable"] = enable + parameter = json.dumps(p) + + code, data = self._Call(VUI_API_ID_SETSWITCH, parameter) + return code + + # 1002 + def GetSwitch(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(VUI_API_ID_GETSWITCH, parameter) + if code == 0: + d = json.loads(data) + return code, d["enable"] + else: + return code, None + + # 1003 + def SetVolume(self, level: int): + p = {} + p["volume"] = level + parameter = json.dumps(p) + + code, data = self._Call(VUI_API_ID_SETVOLUME, parameter) + return code + + # 1006 + def GetVolume(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(VUI_API_ID_GETVOLUME, parameter) + if code == 0: + d = json.loads(data) + return code, d["volume"] + else: + return code, None + + # 1005 + def SetBrightness(self, level: int): + p = {} + p["brightness"] = level + parameter = json.dumps(p) + + code, data = self._Call(VUI_API_ID_SETBRIGHTNESS, parameter) + return code + + # 1006 + def GetBrightness(self): + p = {} + parameter = json.dumps(p) + + code, data = self._Call(VUI_API_ID_GETBRIGHTNESS, parameter) + if code == 0: + d = json.loads(data) + return code, d["brightness"] + else: return code, None \ No newline at end of file diff --git a/unitree_sdk2py/idl/__init__.py b/unitree_sdk2py/idl/__init__.py index d11617e..caddce7 100644 --- a/unitree_sdk2py/idl/__init__.py +++ b/unitree_sdk2py/idl/__init__.py @@ -1,10 +1,10 @@ -from . import builtin_interfaces, geometry_msgs, sensor_msgs, std_msgs, unitree_go, unitree_api - -__all__ = [ - "builtin_interfaces", - "geometry_msgs", - "sensor_msgs", - "std_msgs", - "unitree_go", - "unitree_api", -] +from . import builtin_interfaces, geometry_msgs, sensor_msgs, std_msgs, unitree_go, unitree_api + +__all__ = [ + "builtin_interfaces", + "geometry_msgs", + "sensor_msgs", + "std_msgs", + "unitree_go", + "unitree_api", +] diff --git a/unitree_sdk2py/idl/builtin_interfaces/__init__.py b/unitree_sdk2py/idl/builtin_interfaces/__init__.py index c0397fd..f0817be 100644 --- a/unitree_sdk2py/idl/builtin_interfaces/__init__.py +++ b/unitree_sdk2py/idl/builtin_interfaces/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: builtin_interfaces - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: builtin_interfaces + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/builtin_interfaces/msg/__init__.py b/unitree_sdk2py/idl/builtin_interfaces/msg/__init__.py index b791398..88881b8 100644 --- a/unitree_sdk2py/idl/builtin_interfaces/msg/__init__.py +++ b/unitree_sdk2py/idl/builtin_interfaces/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: builtin_interfaces.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: builtin_interfaces.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/_Time_.py b/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/_Time_.py index 970c671..2fa55de 100644 --- a/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/_Time_.py +++ b/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/_Time_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: builtin_interfaces.msg.dds_ - IDL file: Time_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import builtin_interfaces - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Time_(idl.IdlStruct, typename="builtin_interfaces.msg.dds_.Time_"): - sec: types.int32 - nanosec: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: builtin_interfaces.msg.dds_ + IDL file: Time_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import builtin_interfaces + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Time_(idl.IdlStruct, typename="builtin_interfaces.msg.dds_.Time_"): + sec: types.int32 + nanosec: types.uint32 + + diff --git a/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/__init__.py b/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/__init__.py index c3f9730..2ebc522 100644 --- a/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/builtin_interfaces/msg/dds_/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: builtin_interfaces.msg.dds_ - -""" - -from ._Time_ import Time_ -__all__ = ["Time_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: builtin_interfaces.msg.dds_ + +""" + +from ._Time_ import Time_ +__all__ = ["Time_", ] diff --git a/unitree_sdk2py/idl/default.py b/unitree_sdk2py/idl/default.py index 821a3a3..ab8ca0c 100644 --- a/unitree_sdk2py/idl/default.py +++ b/unitree_sdk2py/idl/default.py @@ -1,205 +1,205 @@ -from .builtin_interfaces.msg.dds_ import * -from .std_msgs.msg.dds_ import * -from .geometry_msgs.msg.dds_ import * -from .nav_msgs.msg.dds_ import * -from .sensor_msgs.msg.dds_ import * -from .unitree_go.msg.dds_ import * -from .unitree_api.msg.dds_ import * - - -""" -" builtin_interfaces_msgs.msg.dds_ dafault -""" -def builtin_interfaces_msgs_msg_dds__Time_(): - return Time_(0, 0) - - -""" -" std_msgs.msg.dds_ dafault -""" -def std_msgs_msg_dds__Header_(): - return Header_(builtin_interfaces_msgs_msg_dds__Time_(), "") - -def std_msgs_msg_dds__String_(): - return String_("") - - -""" -" geometry_msgs.msg.dds_ dafault -""" -def geometry_msgs_msg_dds__Point_(): - return Point_(0.0, 0.0, 0.0) - -def geometry_msgs_msg_dds__Point32_(): - return Point32_(0.0, 0.0, 0.0) - -def geometry_msgs_msg_dds__PointStamped_(): - return PointStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Point_()) - -def geometry_msgs_msg_dds__Quaternion_(): - return Quaternion_(0.0, 0.0, 0.0, 0.0) - -def geometry_msgs_msg_dds__Vector3_(): - return Vector3_(0.0, 0.0, 0.0) - -def geometry_msgs_msg_dds__Pose_(): - return Pose_(geometry_msgs_msg_dds__Point_(), geometry_msgs_msg_dds__Quaternion_()) - -def geometry_msgs_msg_dds__Pose2D_(): - return Pose2D_(0.0, 0.0, 0.0) - -def geometry_msgs_msg_dds__PoseStamped_(): - return PoseStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Pose_()) - -def geometry_msgs_msg_dds__PoseWithCovariance_(): - return PoseWithCovariance_(geometry_msgs_msg_dds__Pose_(), [ - 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 - ]) - -def geometry_msgs_msg_dds__PoseWithCovarianceStamped_(): - return PoseWithCovarianceStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__PoseWithCovariance_()) - -def geometry_msgs_msg_dds__QuaternionStamped_(): - return QuaternionStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Quaternion_()) - -def geometry_msgs_msg_dds__Twist_(): - return Twist_(geometry_msgs_msg_dds__Vector3_(), geometry_msgs_msg_dds__Vector3_()) - -def geometry_msgs_msg_dds__TwistStamped_(): - return TwistStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Twist_()) - -def geometry_msgs_msg_dds__TwistWithCovariance_(): - return TwistWithCovariance_(geometry_msgs_msg_dds__Twist_(), [ - 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 - ]) - -def geometry_msgs_msg_dds__TwistWithCovarianceStamped_(): - return TwistWithCovarianceStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__TwistWithCovariance_()) - - -""" -" nav_msgs.msg.dds_ dafault -""" -def nav_msgs_msg_dds__MapMetaData_(): - return MapMetaData_(builtin_interfaces_msgs_msg_dds__Time_(), 0, 0, geometry_msgs_msg_dds__Pose_()) - -def nav_msgs_msg_dds__OccupancyGrid_(): - return OccupancyGrid_(std_msgs_msg_dds__Header_(), nav_msgs_msg_dds__MapMetaData_(), []) - -def nav_msgs_msg_dds__Odometry_(): - return Odometry_(std_msgs_msg_dds__Header_(), "", geometry_msgs_msg_dds__PoseWithCovariance_(), geometry_msgs_msg_dds__TwistWithCovariance_()) - - -""" -" sensor_msgs.msg.dds_ dafault -""" -def sensor_msgs_msg_dds__PointField_Constants_PointField_(): - return PointField_("", 0, 0, 0) - -def sensor_msgs_msg_dds__PointField_Constants_PointCloud2_(): - return PointCloud2_(std_msgs_msg_dds__Header_(), 0, 0, [], False, 0, 0, [], False) - - -""" -" unitree_go.msg.dds_ dafault -""" -def unitree_go_msg_dds__AudioData_(): - return AudioData_(0, []) - -def unitree_go_msg_dds__BmsCmd_(): - return BmsCmd_(0, [0, 0, 0]) - -def unitree_go_msg_dds__BmsState_(): - return BmsState_(0, 0, 0, 0, 0, 0, [0, 0], [0, 0], [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) - -def unitree_go_msg_dds__Error_(): - return Error_(0, 0) - -def unitree_go_msg_dds__Go2FrontVideoData_(): - return Go2FrontVideoData_(0, [], [], []) - -def unitree_go_msg_dds__HeightMap_(): - return HeightMap_(0.0, "", 0.0, 0, 0, [0.0, 0.0], []) - -def unitree_go_msg_dds__IMUState_(): - return IMUState_([0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0], 0) - -def unitree_go_msg_dds__InterfaceConfig_(): - return InterfaceConfig_(0, 0, [0, 0]) - -def unitree_go_msg_dds__LidarState_(): - return LidarState_(0.0, "", "", "", 0.0, 0.0, 0, 0.0, 0.0, 0, 0, 0.0, 0.0, [0.0, 0.0, 0.0], 0.0, 0, 0) - -def unitree_go_msg_dds__MotorCmd_(): - return MotorCmd_(0, 0.0, 0.0, 0.0, 0.0, 0.0, [0, 0, 0]) - -def unitree_go_msg_dds__MotorState_(): - return MotorState_(0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0, 0, [0, 0]) - -def unitree_go_msg_dds__LowCmd_(): - return LowCmd_([0, 0], 0, 0, [0, 0], [0, 0], 0, [unitree_go_msg_dds__MotorCmd_() for i in range(20)], unitree_go_msg_dds__BmsCmd_(), - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], [0, 0], 0, 0, 0) - -def unitree_go_msg_dds__LowState_(): - return LowState_([0, 0], 0, 0, [0, 0], [0, 0], 0, unitree_go_msg_dds__IMUState_(), [unitree_go_msg_dds__MotorState_() for i in range(20)], - unitree_go_msg_dds__BmsState_(), [0, 0, 0, 0], [0, 0, 0, 0], 0, - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], - 0, 0, 0, 0, 0.0, 0.0, [0, 0, 0, 0], 0, 0) - -def unitree_go_msg_dds__Req_(): - return Req_("", "") - -def unitree_go_msg_dds__Res_(): - return Res_("", [], "") - -def unitree_go_msg_dds__TimeSpec_(): - return TimeSpec_(0, 0) - -def unitree_go_msg_dds__PathPoint_(): - return PathPoint_(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0) - -def unitree_go_msg_dds__SportModeState_(): - return SportModeState_(unitree_go_msg_dds__TimeSpec_(), 0, unitree_go_msg_dds__IMUState_(), 0, 0, 0, 0.0, [0.0, 0.0, 0.0], 0.0, - [0.0, 0.0, 0.0], 0.0, [0.0, 0.0, 0.0, 0.0], [0, 0, 0, 0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], - [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],[unitree_go_msg_dds__PathPoint_() for i in range(10)]) - -def unitree_go_msg_dds__UwbState_(): - return UwbState_([0, 0], 0, 0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, [0.0, 0.0], 0, 0, 0) - -def unitree_go_msg_dds__UwbSwitch_(): - return UwbSwitch_(0) - -def unitree_go_msg_dds__WirelessController_(): - return WirelessController_(0.0, 0.0, 0.0, 0.0, 0) - - -""" -" unitree_api.msg.dds_ dafault -""" -def unitree_api_msg_dds__RequestIdentity_(): - return RequestIdentity_(0, 0) - -def unitree_api_msg_dds__RequestLease_(): - return RequestLease_(0) - -def unitree_api_msg_dds__RequestPolicy_(): - return RequestPolicy_(0, False) - -def unitree_api_msg_dds__RequestHeader_(): - return RequestHeader_(unitree_api_msg_dds__RequestIdentity_(), unitree_api_msg_dds__RequestLease_(), unitree_api_msg_dds__RequestPolicy_()) - -def unitree_api_msg_dds__Request_(): - return Request_(unitree_api_msg_dds__RequestHeader_(), "", []) - -def unitree_api_msg_dds__ResponseStatus_(): - return ResponseStatus_(0) - -def unitree_api_msg_dds__ResponseHeader_(): - return ResponseHeader_(unitree_api_msg_dds__RequestIdentity_(), unitree_api_msg_dds__ResponseStatus_()) - -def unitree_api_msg_dds__Response_(): - return Response_(unitree_api_msg_dds__ResponseHeader_(), "", []) - +from .builtin_interfaces.msg.dds_ import * +from .std_msgs.msg.dds_ import * +from .geometry_msgs.msg.dds_ import * +from .nav_msgs.msg.dds_ import * +from .sensor_msgs.msg.dds_ import * +from .unitree_go.msg.dds_ import * +from .unitree_api.msg.dds_ import * + + +""" +" builtin_interfaces_msgs.msg.dds_ dafault +""" +def builtin_interfaces_msgs_msg_dds__Time_(): + return Time_(0, 0) + + +""" +" std_msgs.msg.dds_ dafault +""" +def std_msgs_msg_dds__Header_(): + return Header_(builtin_interfaces_msgs_msg_dds__Time_(), "") + +def std_msgs_msg_dds__String_(): + return String_("") + + +""" +" geometry_msgs.msg.dds_ dafault +""" +def geometry_msgs_msg_dds__Point_(): + return Point_(0.0, 0.0, 0.0) + +def geometry_msgs_msg_dds__Point32_(): + return Point32_(0.0, 0.0, 0.0) + +def geometry_msgs_msg_dds__PointStamped_(): + return PointStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Point_()) + +def geometry_msgs_msg_dds__Quaternion_(): + return Quaternion_(0.0, 0.0, 0.0, 0.0) + +def geometry_msgs_msg_dds__Vector3_(): + return Vector3_(0.0, 0.0, 0.0) + +def geometry_msgs_msg_dds__Pose_(): + return Pose_(geometry_msgs_msg_dds__Point_(), geometry_msgs_msg_dds__Quaternion_()) + +def geometry_msgs_msg_dds__Pose2D_(): + return Pose2D_(0.0, 0.0, 0.0) + +def geometry_msgs_msg_dds__PoseStamped_(): + return PoseStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Pose_()) + +def geometry_msgs_msg_dds__PoseWithCovariance_(): + return PoseWithCovariance_(geometry_msgs_msg_dds__Pose_(), [ + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 + ]) + +def geometry_msgs_msg_dds__PoseWithCovarianceStamped_(): + return PoseWithCovarianceStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__PoseWithCovariance_()) + +def geometry_msgs_msg_dds__QuaternionStamped_(): + return QuaternionStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Quaternion_()) + +def geometry_msgs_msg_dds__Twist_(): + return Twist_(geometry_msgs_msg_dds__Vector3_(), geometry_msgs_msg_dds__Vector3_()) + +def geometry_msgs_msg_dds__TwistStamped_(): + return TwistStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__Twist_()) + +def geometry_msgs_msg_dds__TwistWithCovariance_(): + return TwistWithCovariance_(geometry_msgs_msg_dds__Twist_(), [ + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 + ]) + +def geometry_msgs_msg_dds__TwistWithCovarianceStamped_(): + return TwistWithCovarianceStamped_(std_msgs_msg_dds__Header_(), geometry_msgs_msg_dds__TwistWithCovariance_()) + + +""" +" nav_msgs.msg.dds_ dafault +""" +def nav_msgs_msg_dds__MapMetaData_(): + return MapMetaData_(builtin_interfaces_msgs_msg_dds__Time_(), 0, 0, geometry_msgs_msg_dds__Pose_()) + +def nav_msgs_msg_dds__OccupancyGrid_(): + return OccupancyGrid_(std_msgs_msg_dds__Header_(), nav_msgs_msg_dds__MapMetaData_(), []) + +def nav_msgs_msg_dds__Odometry_(): + return Odometry_(std_msgs_msg_dds__Header_(), "", geometry_msgs_msg_dds__PoseWithCovariance_(), geometry_msgs_msg_dds__TwistWithCovariance_()) + + +""" +" sensor_msgs.msg.dds_ dafault +""" +def sensor_msgs_msg_dds__PointField_Constants_PointField_(): + return PointField_("", 0, 0, 0) + +def sensor_msgs_msg_dds__PointField_Constants_PointCloud2_(): + return PointCloud2_(std_msgs_msg_dds__Header_(), 0, 0, [], False, 0, 0, [], False) + + +""" +" unitree_go.msg.dds_ dafault +""" +def unitree_go_msg_dds__AudioData_(): + return AudioData_(0, []) + +def unitree_go_msg_dds__BmsCmd_(): + return BmsCmd_(0, [0, 0, 0]) + +def unitree_go_msg_dds__BmsState_(): + return BmsState_(0, 0, 0, 0, 0, 0, [0, 0], [0, 0], [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) + +def unitree_go_msg_dds__Error_(): + return Error_(0, 0) + +def unitree_go_msg_dds__Go2FrontVideoData_(): + return Go2FrontVideoData_(0, [], [], []) + +def unitree_go_msg_dds__HeightMap_(): + return HeightMap_(0.0, "", 0.0, 0, 0, [0.0, 0.0], []) + +def unitree_go_msg_dds__IMUState_(): + return IMUState_([0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0], 0) + +def unitree_go_msg_dds__InterfaceConfig_(): + return InterfaceConfig_(0, 0, [0, 0]) + +def unitree_go_msg_dds__LidarState_(): + return LidarState_(0.0, "", "", "", 0.0, 0.0, 0, 0.0, 0.0, 0, 0, 0.0, 0.0, [0.0, 0.0, 0.0], 0.0, 0, 0) + +def unitree_go_msg_dds__MotorCmd_(): + return MotorCmd_(0, 0.0, 0.0, 0.0, 0.0, 0.0, [0, 0, 0]) + +def unitree_go_msg_dds__MotorState_(): + return MotorState_(0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0, 0, [0, 0]) + +def unitree_go_msg_dds__LowCmd_(): + return LowCmd_([0, 0], 0, 0, [0, 0], [0, 0], 0, [unitree_go_msg_dds__MotorCmd_() for i in range(20)], unitree_go_msg_dds__BmsCmd_(), + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], [0, 0], 0, 0, 0) + +def unitree_go_msg_dds__LowState_(): + return LowState_([0, 0], 0, 0, [0, 0], [0, 0], 0, unitree_go_msg_dds__IMUState_(), [unitree_go_msg_dds__MotorState_() for i in range(20)], + unitree_go_msg_dds__BmsState_(), [0, 0, 0, 0], [0, 0, 0, 0], 0, + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + 0, 0, 0, 0, 0.0, 0.0, [0, 0, 0, 0], 0, 0) + +def unitree_go_msg_dds__Req_(): + return Req_("", "") + +def unitree_go_msg_dds__Res_(): + return Res_("", [], "") + +def unitree_go_msg_dds__TimeSpec_(): + return TimeSpec_(0, 0) + +def unitree_go_msg_dds__PathPoint_(): + return PathPoint_(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0) + +def unitree_go_msg_dds__SportModeState_(): + return SportModeState_(unitree_go_msg_dds__TimeSpec_(), 0, unitree_go_msg_dds__IMUState_(), 0, 0, 0, 0.0, [0.0, 0.0, 0.0], 0.0, + [0.0, 0.0, 0.0], 0.0, [0.0, 0.0, 0.0, 0.0], [0, 0, 0, 0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], + [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],[unitree_go_msg_dds__PathPoint_() for i in range(10)]) + +def unitree_go_msg_dds__UwbState_(): + return UwbState_([0, 0], 0, 0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, [0.0, 0.0], 0, 0, 0) + +def unitree_go_msg_dds__UwbSwitch_(): + return UwbSwitch_(0) + +def unitree_go_msg_dds__WirelessController_(): + return WirelessController_(0.0, 0.0, 0.0, 0.0, 0) + + +""" +" unitree_api.msg.dds_ dafault +""" +def unitree_api_msg_dds__RequestIdentity_(): + return RequestIdentity_(0, 0) + +def unitree_api_msg_dds__RequestLease_(): + return RequestLease_(0) + +def unitree_api_msg_dds__RequestPolicy_(): + return RequestPolicy_(0, False) + +def unitree_api_msg_dds__RequestHeader_(): + return RequestHeader_(unitree_api_msg_dds__RequestIdentity_(), unitree_api_msg_dds__RequestLease_(), unitree_api_msg_dds__RequestPolicy_()) + +def unitree_api_msg_dds__Request_(): + return Request_(unitree_api_msg_dds__RequestHeader_(), "", []) + +def unitree_api_msg_dds__ResponseStatus_(): + return ResponseStatus_(0) + +def unitree_api_msg_dds__ResponseHeader_(): + return ResponseHeader_(unitree_api_msg_dds__RequestIdentity_(), unitree_api_msg_dds__ResponseStatus_()) + +def unitree_api_msg_dds__Response_(): + return Response_(unitree_api_msg_dds__ResponseHeader_(), "", []) + diff --git a/unitree_sdk2py/idl/geometry_msgs/__init__.py b/unitree_sdk2py/idl/geometry_msgs/__init__.py index ab19108..7adae08 100644 --- a/unitree_sdk2py/idl/geometry_msgs/__init__.py +++ b/unitree_sdk2py/idl/geometry_msgs/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/__init__.py b/unitree_sdk2py/idl/geometry_msgs/msg/__init__.py index 7d10dec..035d71b 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/__init__.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point32_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point32_.py index 34eefd4..b6a6d05 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point32_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point32_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Point32_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Point32_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Point32_"): - x: types.float32 - y: types.float32 - z: types.float32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Point32_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Point32_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Point32_"): + x: types.float32 + y: types.float32 + z: types.float32 + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PointStamped_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PointStamped_.py index 19de6ae..3d8d63f 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PointStamped_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PointStamped_.py @@ -1,31 +1,31 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: PointStamped_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PointStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PointStamped_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - point: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Point_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: PointStamped_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PointStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PointStamped_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + point: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Point_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point_.py index efbc562..d545444 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Point_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Point_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Point_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Point_"): - x: types.float64 - y: types.float64 - z: types.float64 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Point_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Point_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Point_"): + x: types.float64 + y: types.float64 + z: types.float64 + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose2D_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose2D_.py index c223370..30b390b 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose2D_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose2D_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Pose2D_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Pose2D_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Pose2D_"): - x: types.float64 - y: types.float64 - theta: types.float64 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Pose2D_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Pose2D_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Pose2D_"): + x: types.float64 + y: types.float64 + theta: types.float64 + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseStamped_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseStamped_.py index 7864bb0..9471277 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseStamped_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseStamped_.py @@ -1,32 +1,32 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: PoseStamped_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PoseStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PoseStamped_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Pose_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: PoseStamped_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PoseStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PoseStamped_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Pose_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovarianceStamped_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovarianceStamped_.py index 843d4c8..6d2d983 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovarianceStamped_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovarianceStamped_.py @@ -1,32 +1,32 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: PoseWithCovarianceStamped_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PoseWithCovarianceStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PoseWithCovarianceStamped_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.PoseWithCovariance_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: PoseWithCovarianceStamped_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PoseWithCovarianceStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PoseWithCovarianceStamped_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.PoseWithCovariance_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovariance_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovariance_.py index bd75301..a97f9b9 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovariance_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_PoseWithCovariance_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: PoseWithCovariance_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PoseWithCovariance_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PoseWithCovariance_"): - pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Pose_' - covariance: types.array[types.float64, 36] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: PoseWithCovariance_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PoseWithCovariance_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.PoseWithCovariance_"): + pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Pose_' + covariance: types.array[types.float64, 36] + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose_.py index 2ea78d1..524a318 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Pose_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Pose_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Pose_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Pose_"): - position: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Point_' - orientation: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Quaternion_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Pose_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Pose_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Pose_"): + position: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Point_' + orientation: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Quaternion_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_QuaternionStamped_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_QuaternionStamped_.py index ae2b360..012b80f 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_QuaternionStamped_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_QuaternionStamped_.py @@ -1,32 +1,32 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: QuaternionStamped_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class QuaternionStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.QuaternionStamped_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - quaternion: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Quaternion_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: QuaternionStamped_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class QuaternionStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.QuaternionStamped_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + quaternion: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Quaternion_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Quaternion_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Quaternion_.py index 0a401fb..1651d0f 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Quaternion_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Quaternion_.py @@ -1,30 +1,30 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Quaternion_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Quaternion_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Quaternion_"): - x: types.float64 - y: types.float64 - z: types.float64 - w: types.float64 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Quaternion_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Quaternion_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Quaternion_"): + x: types.float64 + y: types.float64 + z: types.float64 + w: types.float64 + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistStamped_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistStamped_.py index 97aa7c9..b26f27a 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistStamped_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistStamped_.py @@ -1,32 +1,32 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: TwistStamped_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class TwistStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.TwistStamped_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Twist_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: TwistStamped_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class TwistStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.TwistStamped_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Twist_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovarianceStamped_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovarianceStamped_.py index d322b7f..570d23e 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovarianceStamped_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovarianceStamped_.py @@ -1,32 +1,32 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: TwistWithCovarianceStamped_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class TwistWithCovarianceStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.TwistWithCovarianceStamped_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.TwistWithCovariance_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: TwistWithCovarianceStamped_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class TwistWithCovarianceStamped_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.TwistWithCovarianceStamped_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.TwistWithCovariance_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovariance_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovariance_.py index 7281bfc..dea4b88 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovariance_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_TwistWithCovariance_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: TwistWithCovariance_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class TwistWithCovariance_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.TwistWithCovariance_"): - twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Twist_' - covariance: types.array[types.float64, 36] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: TwistWithCovariance_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class TwistWithCovariance_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.TwistWithCovariance_"): + twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Twist_' + covariance: types.array[types.float64, 36] + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Twist_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Twist_.py index 5cd3b23..54ea54d 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Twist_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Twist_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Twist_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Twist_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Twist_"): - linear: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Vector3_' - angular: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Vector3_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Twist_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Twist_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Twist_"): + linear: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Vector3_' + angular: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Vector3_' + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Vector3_.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Vector3_.py index 9cdeb0f..e582cd6 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Vector3_.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/_Vector3_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - IDL file: Vector3_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import geometry_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Vector3_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Vector3_"): - x: types.float64 - y: types.float64 - z: types.float64 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + IDL file: Vector3_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import geometry_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Vector3_(idl.IdlStruct, typename="geometry_msgs.msg.dds_.Vector3_"): + x: types.float64 + y: types.float64 + z: types.float64 + + diff --git a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/__init__.py b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/__init__.py index 68c4fe2..a6a4788 100644 --- a/unitree_sdk2py/idl/geometry_msgs/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/geometry_msgs/msg/dds_/__init__.py @@ -1,23 +1,23 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: geometry_msgs.msg.dds_ - -""" - -from ._Point32_ import Point32_ -from ._Point_ import Point_ -from ._PointStamped_ import PointStamped_ -from ._Pose2D_ import Pose2D_ -from ._Pose_ import Pose_ -from ._PoseStamped_ import PoseStamped_ -from ._PoseWithCovariance_ import PoseWithCovariance_ -from ._PoseWithCovarianceStamped_ import PoseWithCovarianceStamped_ -from ._Quaternion_ import Quaternion_ -from ._QuaternionStamped_ import QuaternionStamped_ -from ._Twist_ import Twist_ -from ._TwistStamped_ import TwistStamped_ -from ._TwistWithCovariance_ import TwistWithCovariance_ -from ._TwistWithCovarianceStamped_ import TwistWithCovarianceStamped_ -from ._Vector3_ import Vector3_ -__all__ = ["Point32_", "Point_", "PointStamped_", "Pose2D_", "Pose_", "PoseStamped_", "PoseWithCovariance_", "PoseWithCovarianceStamped_", "Quaternion_", "QuaternionStamped_", "Twist_", "TwistStamped_", "TwistWithCovariance_", "TwistWithCovarianceStamped_", "Vector3_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: geometry_msgs.msg.dds_ + +""" + +from ._Point32_ import Point32_ +from ._Point_ import Point_ +from ._PointStamped_ import PointStamped_ +from ._Pose2D_ import Pose2D_ +from ._Pose_ import Pose_ +from ._PoseStamped_ import PoseStamped_ +from ._PoseWithCovariance_ import PoseWithCovariance_ +from ._PoseWithCovarianceStamped_ import PoseWithCovarianceStamped_ +from ._Quaternion_ import Quaternion_ +from ._QuaternionStamped_ import QuaternionStamped_ +from ._Twist_ import Twist_ +from ._TwistStamped_ import TwistStamped_ +from ._TwistWithCovariance_ import TwistWithCovariance_ +from ._TwistWithCovarianceStamped_ import TwistWithCovarianceStamped_ +from ._Vector3_ import Vector3_ +__all__ = ["Point32_", "Point_", "PointStamped_", "Pose2D_", "Pose_", "PoseStamped_", "PoseWithCovariance_", "PoseWithCovarianceStamped_", "Quaternion_", "QuaternionStamped_", "Twist_", "TwistStamped_", "TwistWithCovariance_", "TwistWithCovarianceStamped_", "Vector3_", ] diff --git a/unitree_sdk2py/idl/nav_msgs/__init__.py b/unitree_sdk2py/idl/nav_msgs/__init__.py index a2724c2..0ae9ad3 100644 --- a/unitree_sdk2py/idl/nav_msgs/__init__.py +++ b/unitree_sdk2py/idl/nav_msgs/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: nav_msgs - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: nav_msgs + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/nav_msgs/msg/__init__.py b/unitree_sdk2py/idl/nav_msgs/msg/__init__.py index d47683b..e21851f 100644 --- a/unitree_sdk2py/idl/nav_msgs/msg/__init__.py +++ b/unitree_sdk2py/idl/nav_msgs/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: nav_msgs.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: nav_msgs.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/nav_msgs/msg/dds_/_MapMetaData_.py b/unitree_sdk2py/idl/nav_msgs/msg/dds_/_MapMetaData_.py index 9228cd6..7a3ac3a 100644 --- a/unitree_sdk2py/idl/nav_msgs/msg/dds_/_MapMetaData_.py +++ b/unitree_sdk2py/idl/nav_msgs/msg/dds_/_MapMetaData_.py @@ -1,35 +1,35 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: nav_msgs.msg.dds_ - IDL file: MapMetaData_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import nav_msgs - -# if TYPE_CHECKING: -# import builtin_interfaces.msg.dds_ -# import geometry_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class MapMetaData_(idl.IdlStruct, typename="nav_msgs.msg.dds_.MapMetaData_"): - map_load_time: 'unitree_sdk2py.idl.builtin_interfaces.msg.dds_.Time_' - resolution: types.float32 - width: types.uint32 - height: types.uint32 - origin: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Pose_' - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: nav_msgs.msg.dds_ + IDL file: MapMetaData_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import nav_msgs + +# if TYPE_CHECKING: +# import builtin_interfaces.msg.dds_ +# import geometry_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class MapMetaData_(idl.IdlStruct, typename="nav_msgs.msg.dds_.MapMetaData_"): + map_load_time: 'unitree_sdk2py.idl.builtin_interfaces.msg.dds_.Time_' + resolution: types.float32 + width: types.uint32 + height: types.uint32 + origin: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.Pose_' + diff --git a/unitree_sdk2py/idl/nav_msgs/msg/dds_/_OccupancyGrid_.py b/unitree_sdk2py/idl/nav_msgs/msg/dds_/_OccupancyGrid_.py index 0274c58..597be90 100644 --- a/unitree_sdk2py/idl/nav_msgs/msg/dds_/_OccupancyGrid_.py +++ b/unitree_sdk2py/idl/nav_msgs/msg/dds_/_OccupancyGrid_.py @@ -1,33 +1,33 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: nav_msgs.msg.dds_ - IDL file: OccupancyGrid_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import nav_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class OccupancyGrid_(idl.IdlStruct, typename="nav_msgs.msg.dds_.OccupancyGrid_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - info: 'unitree_sdk2py.idl.nav_msgs.msg.dds_.MapMetaData_' - data: types.sequence[types.uint8] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: nav_msgs.msg.dds_ + IDL file: OccupancyGrid_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import nav_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class OccupancyGrid_(idl.IdlStruct, typename="nav_msgs.msg.dds_.OccupancyGrid_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + info: 'unitree_sdk2py.idl.nav_msgs.msg.dds_.MapMetaData_' + data: types.sequence[types.uint8] + + diff --git a/unitree_sdk2py/idl/nav_msgs/msg/dds_/_Odometry_.py b/unitree_sdk2py/idl/nav_msgs/msg/dds_/_Odometry_.py index 054bb5c..920de1b 100644 --- a/unitree_sdk2py/idl/nav_msgs/msg/dds_/_Odometry_.py +++ b/unitree_sdk2py/idl/nav_msgs/msg/dds_/_Odometry_.py @@ -1,35 +1,35 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: nav_msgs.msg.dds_ - IDL file: Odometry_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import nav_msgs - -# if TYPE_CHECKING: -# import geometry_msgs.msg.dds_ -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Odometry_(idl.IdlStruct, typename="nav_msgs.msg.dds_.Odometry_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - child_frame_id: str - pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.PoseWithCovariance_' - twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.TwistWithCovariance_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: nav_msgs.msg.dds_ + IDL file: Odometry_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import nav_msgs + +# if TYPE_CHECKING: +# import geometry_msgs.msg.dds_ +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Odometry_(idl.IdlStruct, typename="nav_msgs.msg.dds_.Odometry_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + child_frame_id: str + pose: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.PoseWithCovariance_' + twist: 'unitree_sdk2py.idl.geometry_msgs.msg.dds_.TwistWithCovariance_' + + diff --git a/unitree_sdk2py/idl/nav_msgs/msg/dds_/__init__.py b/unitree_sdk2py/idl/nav_msgs/msg/dds_/__init__.py index a14e17a..3bba664 100644 --- a/unitree_sdk2py/idl/nav_msgs/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/nav_msgs/msg/dds_/__init__.py @@ -1,11 +1,11 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: nav_msgs.msg.dds_ - -""" - -from ._MapMetaData_ import MapMetaData_ -from ._OccupancyGrid_ import OccupancyGrid_ -from ._Odometry_ import Odometry_ -__all__ = ["MapMetaData_", "OccupancyGrid_", "Odometry_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: nav_msgs.msg.dds_ + +""" + +from ._MapMetaData_ import MapMetaData_ +from ._OccupancyGrid_ import OccupancyGrid_ +from ._Odometry_ import Odometry_ +__all__ = ["MapMetaData_", "OccupancyGrid_", "Odometry_", ] diff --git a/unitree_sdk2py/idl/sensor_msgs/__init__.py b/unitree_sdk2py/idl/sensor_msgs/__init__.py index 984e7e2..5514b08 100644 --- a/unitree_sdk2py/idl/sensor_msgs/__init__.py +++ b/unitree_sdk2py/idl/sensor_msgs/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/sensor_msgs/msg/__init__.py b/unitree_sdk2py/idl/sensor_msgs/msg/__init__.py index 62a2292..0b41de7 100644 --- a/unitree_sdk2py/idl/sensor_msgs/msg/__init__.py +++ b/unitree_sdk2py/idl/sensor_msgs/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/_PointField_.py b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/_PointField_.py index 673aa84..fea385b 100644 --- a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/_PointField_.py +++ b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/_PointField_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs.msg.dds_.PointField_Constants - IDL file: PointField_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import sensor_msgs - -INT8_ = 1 -UINT8_ = 2 -INT16_ = 3 -UINT16_ = 4 -INT32_ = 5 -UINT32_ = 6 -FLOAT32_ = 7 -FLOAT64_ = 8 - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs.msg.dds_.PointField_Constants + IDL file: PointField_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import sensor_msgs + +INT8_ = 1 +UINT8_ = 2 +INT16_ = 3 +UINT16_ = 4 +INT32_ = 5 +UINT32_ = 6 +FLOAT32_ = 7 +FLOAT64_ = 8 + diff --git a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/__init__.py b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/__init__.py index 310fecd..6ee8f53 100644 --- a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/__init__.py +++ b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/PointField_Constants/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs.msg.dds_.PointField_Constants - -""" - -from ._PointField_ import FLOAT32_, FLOAT64_, INT16_, INT32_, INT8_, UINT16_, UINT32_, UINT8_ -__all__ = ["FLOAT32_", "FLOAT64_", "INT16_", "INT32_", "INT8_", "UINT16_", "UINT32_", "UINT8_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs.msg.dds_.PointField_Constants + +""" + +from ._PointField_ import FLOAT32_, FLOAT64_, INT16_, INT32_, INT8_, UINT16_, UINT32_, UINT8_ +__all__ = ["FLOAT32_", "FLOAT64_", "INT16_", "INT32_", "INT8_", "UINT16_", "UINT32_", "UINT8_", ] diff --git a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointCloud2_.py b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointCloud2_.py index ffdf713..cf6b4a8 100644 --- a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointCloud2_.py +++ b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointCloud2_.py @@ -1,39 +1,39 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs.msg.dds_ - IDL file: PointCloud2_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import sensor_msgs - -# if TYPE_CHECKING: -# import std_msgs.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PointCloud2_(idl.IdlStruct, typename="sensor_msgs.msg.dds_.PointCloud2_"): - header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' - height: types.uint32 - width: types.uint32 - fields: types.sequence['unitree_sdk2py.idl.sensor_msgs.msg.dds_.PointField_'] - is_bigendian: bool - point_step: types.uint32 - row_step: types.uint32 - data: types.sequence[types.uint8] - is_dense: bool - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs.msg.dds_ + IDL file: PointCloud2_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import sensor_msgs + +# if TYPE_CHECKING: +# import std_msgs.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PointCloud2_(idl.IdlStruct, typename="sensor_msgs.msg.dds_.PointCloud2_"): + header: 'unitree_sdk2py.idl.std_msgs.msg.dds_.Header_' + height: types.uint32 + width: types.uint32 + fields: types.sequence['unitree_sdk2py.idl.sensor_msgs.msg.dds_.PointField_'] + is_bigendian: bool + point_step: types.uint32 + row_step: types.uint32 + data: types.sequence[types.uint8] + is_dense: bool + + diff --git a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointField_.py b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointField_.py index e62dbf9..ed6bee8 100644 --- a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointField_.py +++ b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/_PointField_.py @@ -1,30 +1,30 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs.msg.dds_ - IDL file: PointField_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import sensor_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PointField_(idl.IdlStruct, typename="sensor_msgs.msg.dds_.PointField_"): - name: str - offset: types.uint32 - datatype: types.uint8 - count: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs.msg.dds_ + IDL file: PointField_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import sensor_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PointField_(idl.IdlStruct, typename="sensor_msgs.msg.dds_.PointField_"): + name: str + offset: types.uint32 + datatype: types.uint8 + count: types.uint32 + + diff --git a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/__init__.py b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/__init__.py index 68e0141..8e0711c 100644 --- a/unitree_sdk2py/idl/sensor_msgs/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/sensor_msgs/msg/dds_/__init__.py @@ -1,11 +1,11 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: sensor_msgs.msg.dds_ - -""" - -from . import PointField_Constants -from ._PointCloud2_ import PointCloud2_ -from ._PointField_ import PointField_ -__all__ = ["PointField_Constants", "PointCloud2_", "PointField_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: sensor_msgs.msg.dds_ + +""" + +from . import PointField_Constants +from ._PointCloud2_ import PointCloud2_ +from ._PointField_ import PointField_ +__all__ = ["PointField_Constants", "PointCloud2_", "PointField_", ] diff --git a/unitree_sdk2py/idl/std_msgs/__init__.py b/unitree_sdk2py/idl/std_msgs/__init__.py index c17a705..bd04a74 100644 --- a/unitree_sdk2py/idl/std_msgs/__init__.py +++ b/unitree_sdk2py/idl/std_msgs/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: std_msgs - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: std_msgs + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/std_msgs/msg/__init__.py b/unitree_sdk2py/idl/std_msgs/msg/__init__.py index 02c8fe3..01b4402 100644 --- a/unitree_sdk2py/idl/std_msgs/msg/__init__.py +++ b/unitree_sdk2py/idl/std_msgs/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: std_msgs.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: std_msgs.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/std_msgs/msg/dds_/_Header_.py b/unitree_sdk2py/idl/std_msgs/msg/dds_/_Header_.py index bd3564f..2e07c65 100644 --- a/unitree_sdk2py/idl/std_msgs/msg/dds_/_Header_.py +++ b/unitree_sdk2py/idl/std_msgs/msg/dds_/_Header_.py @@ -1,32 +1,32 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: std_msgs.msg.dds_ - IDL file: Header_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import std_msgs - -# if TYPE_CHECKING: -# import builtin_interfaces.msg.dds_ - - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Header_(idl.IdlStruct, typename="std_msgs.msg.dds_.Header_"): - stamp: 'unitree_sdk2py.idl.builtin_interfaces.msg.dds_.Time_' - frame_id: str - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: std_msgs.msg.dds_ + IDL file: Header_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import std_msgs + +# if TYPE_CHECKING: +# import builtin_interfaces.msg.dds_ + + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Header_(idl.IdlStruct, typename="std_msgs.msg.dds_.Header_"): + stamp: 'unitree_sdk2py.idl.builtin_interfaces.msg.dds_.Time_' + frame_id: str + + diff --git a/unitree_sdk2py/idl/std_msgs/msg/dds_/_String_.py b/unitree_sdk2py/idl/std_msgs/msg/dds_/_String_.py index 052f122..df1f648 100644 --- a/unitree_sdk2py/idl/std_msgs/msg/dds_/_String_.py +++ b/unitree_sdk2py/idl/std_msgs/msg/dds_/_String_.py @@ -1,27 +1,27 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: std_msgs.msg.dds_ - IDL file: String_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import std_msgs - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class String_(idl.IdlStruct, typename="std_msgs.msg.dds_.String_"): - data: str - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: std_msgs.msg.dds_ + IDL file: String_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import std_msgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class String_(idl.IdlStruct, typename="std_msgs.msg.dds_.String_"): + data: str + + diff --git a/unitree_sdk2py/idl/std_msgs/msg/dds_/__init__.py b/unitree_sdk2py/idl/std_msgs/msg/dds_/__init__.py index f5282e5..c5b7b53 100644 --- a/unitree_sdk2py/idl/std_msgs/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/std_msgs/msg/dds_/__init__.py @@ -1,10 +1,10 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: std_msgs.msg.dds_ - -""" - -from ._Header_ import Header_ -from ._String_ import String_ -__all__ = ["Header_", "String_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: std_msgs.msg.dds_ + +""" + +from ._Header_ import Header_ +from ._String_ import String_ +__all__ = ["Header_", "String_", ] diff --git a/unitree_sdk2py/idl/unitree_api/__init__.py b/unitree_sdk2py/idl/unitree_api/__init__.py index e6546ff..4ccefe7 100644 --- a/unitree_sdk2py/idl/unitree_api/__init__.py +++ b/unitree_sdk2py/idl/unitree_api/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/unitree_api/msg/__init__.py b/unitree_sdk2py/idl/unitree_api/msg/__init__.py index bbf9fde..5ba5860 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/__init__.py +++ b/unitree_sdk2py/idl/unitree_api/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestHeader_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestHeader_.py index 57d67a0..5ef4855 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestHeader_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestHeader_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: RequestHeader_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class RequestHeader_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestHeader_"): - identity: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestIdentity_' - lease: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestLease_' - policy: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestPolicy_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: RequestHeader_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class RequestHeader_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestHeader_"): + identity: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestIdentity_' + lease: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestLease_' + policy: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestPolicy_' + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestIdentity_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestIdentity_.py index a891b54..a4f2487 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestIdentity_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestIdentity_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: RequestIdentity_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class RequestIdentity_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestIdentity_"): - id: types.int64 - api_id: types.int64 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: RequestIdentity_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class RequestIdentity_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestIdentity_"): + id: types.int64 + api_id: types.int64 + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestLease_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestLease_.py index 32cef0f..6fb32dd 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestLease_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestLease_.py @@ -1,27 +1,27 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: RequestLease_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class RequestLease_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestLease_"): - id: types.int64 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: RequestLease_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class RequestLease_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestLease_"): + id: types.int64 + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestPolicy_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestPolicy_.py index aa7ef2f..63a7df2 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestPolicy_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_RequestPolicy_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: RequestPolicy_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class RequestPolicy_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestPolicy_"): - priority: types.int32 - noreply: bool - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: RequestPolicy_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class RequestPolicy_(idl.IdlStruct, typename="unitree_api.msg.dds_.RequestPolicy_"): + priority: types.int32 + noreply: bool + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_Request_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_Request_.py index 39c6b43..ef31a1f 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_Request_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_Request_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: Request_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Request_(idl.IdlStruct, typename="unitree_api.msg.dds_.Request_"): - header: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestHeader_' - parameter: str - binary: types.sequence[types.uint8] - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: Request_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Request_(idl.IdlStruct, typename="unitree_api.msg.dds_.Request_"): + header: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestHeader_' + parameter: str + binary: types.sequence[types.uint8] + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseHeader_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseHeader_.py index ef47340..88ec8db 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseHeader_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseHeader_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: ResponseHeader_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class ResponseHeader_(idl.IdlStruct, typename="unitree_api.msg.dds_.ResponseHeader_"): - identity: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestIdentity_' - status: 'unitree_sdk2py.idl.unitree_api.msg.dds_.ResponseStatus_' - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: ResponseHeader_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class ResponseHeader_(idl.IdlStruct, typename="unitree_api.msg.dds_.ResponseHeader_"): + identity: 'unitree_sdk2py.idl.unitree_api.msg.dds_.RequestIdentity_' + status: 'unitree_sdk2py.idl.unitree_api.msg.dds_.ResponseStatus_' + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseStatus_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseStatus_.py index 92c0b1b..65c62e6 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseStatus_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_ResponseStatus_.py @@ -1,27 +1,27 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: ResponseStatus_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class ResponseStatus_(idl.IdlStruct, typename="unitree_api.msg.dds_.ResponseStatus_"): - code: types.int32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: ResponseStatus_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class ResponseStatus_(idl.IdlStruct, typename="unitree_api.msg.dds_.ResponseStatus_"): + code: types.int32 + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/_Response_.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/_Response_.py index c743651..9e6b141 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/_Response_.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/_Response_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - IDL file: Response_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_api - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Response_(idl.IdlStruct, typename="unitree_api.msg.dds_.Response_"): - header: 'unitree_sdk2py.idl.unitree_api.msg.dds_.ResponseHeader_' - data: str - binary: types.sequence[types.uint8] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + IDL file: Response_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_api + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Response_(idl.IdlStruct, typename="unitree_api.msg.dds_.Response_"): + header: 'unitree_sdk2py.idl.unitree_api.msg.dds_.ResponseHeader_' + data: str + binary: types.sequence[types.uint8] + + diff --git a/unitree_sdk2py/idl/unitree_api/msg/dds_/__init__.py b/unitree_sdk2py/idl/unitree_api/msg/dds_/__init__.py index 1e4c9f8..942e0ba 100644 --- a/unitree_sdk2py/idl/unitree_api/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/unitree_api/msg/dds_/__init__.py @@ -1,16 +1,16 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.10.2 - Module: unitree_api.msg.dds_ - -""" - -from ._RequestHeader_ import RequestHeader_ -from ._RequestIdentity_ import RequestIdentity_ -from ._RequestLease_ import RequestLease_ -from ._RequestPolicy_ import RequestPolicy_ -from ._Request_ import Request_ -from ._ResponseHeader_ import ResponseHeader_ -from ._ResponseStatus_ import ResponseStatus_ -from ._Response_ import Response_ -__all__ = ["RequestHeader_", "RequestIdentity_", "RequestLease_", "RequestPolicy_", "Request_", "ResponseHeader_", "ResponseStatus_", "Response_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.2 + Module: unitree_api.msg.dds_ + +""" + +from ._RequestHeader_ import RequestHeader_ +from ._RequestIdentity_ import RequestIdentity_ +from ._RequestLease_ import RequestLease_ +from ._RequestPolicy_ import RequestPolicy_ +from ._Request_ import Request_ +from ._ResponseHeader_ import ResponseHeader_ +from ._ResponseStatus_ import ResponseStatus_ +from ._Response_ import Response_ +__all__ = ["RequestHeader_", "RequestIdentity_", "RequestLease_", "RequestPolicy_", "Request_", "ResponseHeader_", "ResponseStatus_", "Response_", ] diff --git a/unitree_sdk2py/idl/unitree_go/__init__.py b/unitree_sdk2py/idl/unitree_go/__init__.py index b553006..bbd0e36 100644 --- a/unitree_sdk2py/idl/unitree_go/__init__.py +++ b/unitree_sdk2py/idl/unitree_go/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go - -""" - -from . import msg -__all__ = ["msg", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go + +""" + +from . import msg +__all__ = ["msg", ] diff --git a/unitree_sdk2py/idl/unitree_go/msg/__init__.py b/unitree_sdk2py/idl/unitree_go/msg/__init__.py index f8cae9b..984b9fd 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/__init__.py +++ b/unitree_sdk2py/idl/unitree_go/msg/__init__.py @@ -1,9 +1,9 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg - -""" - -from . import dds_ -__all__ = ["dds_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg + +""" + +from . import dds_ +__all__ = ["dds_", ] diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_AudioData_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_AudioData_.py index 27913c9..7898a51 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_AudioData_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_AudioData_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: AudioData_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class AudioData_(idl.IdlStruct, typename="unitree_go.msg.dds_.AudioData_"): - time_frame: types.uint64 - data: types.sequence[types.uint8] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: AudioData_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class AudioData_(idl.IdlStruct, typename="unitree_go.msg.dds_.AudioData_"): + time_frame: types.uint64 + data: types.sequence[types.uint8] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsCmd_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsCmd_.py index 5da647e..3cba831 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsCmd_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsCmd_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: BmsCmd_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class BmsCmd_(idl.IdlStruct, typename="unitree_go.msg.dds_.BmsCmd_"): - off: types.uint8 - reserve: types.array[types.uint8, 3] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: BmsCmd_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class BmsCmd_(idl.IdlStruct, typename="unitree_go.msg.dds_.BmsCmd_"): + off: types.uint8 + reserve: types.array[types.uint8, 3] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsState_.py index af635e8..7e47677 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_BmsState_.py @@ -1,35 +1,35 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: BmsState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class BmsState_(idl.IdlStruct, typename="unitree_go.msg.dds_.BmsState_"): - version_high: types.uint8 - version_low: types.uint8 - status: types.uint8 - soc: types.uint8 - current: types.int32 - cycle: types.uint16 - bq_ntc: types.array[types.uint8, 2] - mcu_ntc: types.array[types.uint8, 2] - cell_vol: types.array[types.uint16, 15] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: BmsState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class BmsState_(idl.IdlStruct, typename="unitree_go.msg.dds_.BmsState_"): + version_high: types.uint8 + version_low: types.uint8 + status: types.uint8 + soc: types.uint8 + current: types.int32 + cycle: types.uint16 + bq_ntc: types.array[types.uint8, 2] + mcu_ntc: types.array[types.uint8, 2] + cell_vol: types.array[types.uint16, 15] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Error_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Error_.py index c338c69..0a8cdc9 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Error_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Error_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: Error_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Error_(idl.IdlStruct, typename="unitree_go.msg.dds_.Error_"): - source: types.uint32 - state: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: Error_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Error_(idl.IdlStruct, typename="unitree_go.msg.dds_.Error_"): + source: types.uint32 + state: types.uint32 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Go2FrontVideoData_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Go2FrontVideoData_.py index 04d245b..d8e1f87 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Go2FrontVideoData_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Go2FrontVideoData_.py @@ -1,30 +1,30 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: Go2FrontVideoData_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Go2FrontVideoData_(idl.IdlStruct, typename="unitree_go.msg.dds_.Go2FrontVideoData_"): - time_frame: types.uint64 - video720p: types.sequence[types.uint8] - video360p: types.sequence[types.uint8] - video180p: types.sequence[types.uint8] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: Go2FrontVideoData_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Go2FrontVideoData_(idl.IdlStruct, typename="unitree_go.msg.dds_.Go2FrontVideoData_"): + time_frame: types.uint64 + video720p: types.sequence[types.uint8] + video360p: types.sequence[types.uint8] + video180p: types.sequence[types.uint8] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_HeightMap_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_HeightMap_.py index 48168da..6364700 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_HeightMap_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_HeightMap_.py @@ -1,33 +1,33 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: HeightMap_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class HeightMap_(idl.IdlStruct, typename="unitree_go.msg.dds_.HeightMap_"): - stamp: types.float64 - frame_id: str - resolution: types.float32 - width: types.uint32 - height: types.uint32 - origin: types.array[types.float32, 2] - data: types.sequence[types.float32] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: HeightMap_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class HeightMap_(idl.IdlStruct, typename="unitree_go.msg.dds_.HeightMap_"): + stamp: types.float64 + frame_id: str + resolution: types.float32 + width: types.uint32 + height: types.uint32 + origin: types.array[types.float32, 2] + data: types.sequence[types.float32] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_IMUState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_IMUState_.py index e48908f..7f29ad2 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_IMUState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_IMUState_.py @@ -1,31 +1,31 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: IMUState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class IMUState_(idl.IdlStruct, typename="unitree_go.msg.dds_.IMUState_"): - quaternion: types.array[types.float32, 4] - gyroscope: types.array[types.float32, 3] - accelerometer: types.array[types.float32, 3] - rpy: types.array[types.float32, 3] - temperature: types.uint8 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: IMUState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class IMUState_(idl.IdlStruct, typename="unitree_go.msg.dds_.IMUState_"): + quaternion: types.array[types.float32, 4] + gyroscope: types.array[types.float32, 3] + accelerometer: types.array[types.float32, 3] + rpy: types.array[types.float32, 3] + temperature: types.uint8 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_InterfaceConfig_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_InterfaceConfig_.py index 5efbd64..b06d1dc 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_InterfaceConfig_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_InterfaceConfig_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: InterfaceConfig_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class InterfaceConfig_(idl.IdlStruct, typename="unitree_go.msg.dds_.InterfaceConfig_"): - mode: types.uint8 - value: types.uint8 - reserve: types.array[types.uint8, 2] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: InterfaceConfig_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class InterfaceConfig_(idl.IdlStruct, typename="unitree_go.msg.dds_.InterfaceConfig_"): + mode: types.uint8 + value: types.uint8 + reserve: types.array[types.uint8, 2] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_LidarState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_LidarState_.py index 6861068..b34d0b3 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_LidarState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_LidarState_.py @@ -1,43 +1,43 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: LidarState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class LidarState_(idl.IdlStruct, typename="unitree_go.msg.dds_.LidarState_"): - stamp: types.float64 - firmware_version: str - software_version: str - sdk_version: str - sys_rotation_speed: types.float32 - com_rotation_speed: types.float32 - error_state: types.uint8 - cloud_frequency: types.float32 - cloud_packet_loss_rate: types.float32 - cloud_size: types.uint32 - cloud_scan_num: types.uint32 - imu_frequency: types.float32 - imu_packet_loss_rate: types.float32 - imu_rpy: types.array[types.float32, 3] - serial_recv_stamp: types.float64 - serial_buffer_size: types.uint32 - serial_buffer_read: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: LidarState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class LidarState_(idl.IdlStruct, typename="unitree_go.msg.dds_.LidarState_"): + stamp: types.float64 + firmware_version: str + software_version: str + sdk_version: str + sys_rotation_speed: types.float32 + com_rotation_speed: types.float32 + error_state: types.uint8 + cloud_frequency: types.float32 + cloud_packet_loss_rate: types.float32 + cloud_size: types.uint32 + cloud_scan_num: types.uint32 + imu_frequency: types.float32 + imu_packet_loss_rate: types.float32 + imu_rpy: types.array[types.float32, 3] + serial_recv_stamp: types.float64 + serial_buffer_size: types.uint32 + serial_buffer_read: types.uint32 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowCmd_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowCmd_.py index bcd4781..b1069af 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowCmd_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowCmd_.py @@ -1,40 +1,40 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: LowCmd_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class LowCmd_(idl.IdlStruct, typename="unitree_go.msg.dds_.LowCmd_"): - head: types.array[types.uint8, 2] - level_flag: types.uint8 - frame_reserve: types.uint8 - sn: types.array[types.uint32, 2] - version: types.array[types.uint32, 2] - bandwidth: types.uint16 - motor_cmd: types.array['unitree_sdk2py.idl.unitree_go.msg.dds_.MotorCmd_', 20] - bms_cmd: 'unitree_sdk2py.idl.unitree_go.msg.dds_.BmsCmd_' - wireless_remote: types.array[types.uint8, 40] - led: types.array[types.uint8, 12] - fan: types.array[types.uint8, 2] - gpio: types.uint8 - reserve: types.uint32 - crc: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: LowCmd_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class LowCmd_(idl.IdlStruct, typename="unitree_go.msg.dds_.LowCmd_"): + head: types.array[types.uint8, 2] + level_flag: types.uint8 + frame_reserve: types.uint8 + sn: types.array[types.uint32, 2] + version: types.array[types.uint32, 2] + bandwidth: types.uint16 + motor_cmd: types.array['unitree_sdk2py.idl.unitree_go.msg.dds_.MotorCmd_', 20] + bms_cmd: 'unitree_sdk2py.idl.unitree_go.msg.dds_.BmsCmd_' + wireless_remote: types.array[types.uint8, 40] + led: types.array[types.uint8, 12] + fan: types.array[types.uint8, 2] + gpio: types.uint8 + reserve: types.uint32 + crc: types.uint32 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowState_.py index 79ecbe6..23f7336 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_LowState_.py @@ -1,48 +1,48 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: LowState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class LowState_(idl.IdlStruct, typename="unitree_go.msg.dds_.LowState_"): - head: types.array[types.uint8, 2] - level_flag: types.uint8 - frame_reserve: types.uint8 - sn: types.array[types.uint32, 2] - version: types.array[types.uint32, 2] - bandwidth: types.uint16 - imu_state: 'unitree_sdk2py.idl.unitree_go.msg.dds_.IMUState_' - motor_state: types.array['unitree_sdk2py.idl.unitree_go.msg.dds_.MotorState_', 20] - bms_state: 'unitree_sdk2py.idl.unitree_go.msg.dds_.BmsState_' - foot_force: types.array[types.int16, 4] - foot_force_est: types.array[types.int16, 4] - tick: types.uint32 - wireless_remote: types.array[types.uint8, 40] - bit_flag: types.uint8 - adc_reel: types.float32 - temperature_ntc1: types.uint8 - temperature_ntc2: types.uint8 - power_v: types.float32 - power_a: types.float32 - fan_frequency: types.array[types.uint16, 4] - reserve: types.uint32 - crc: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: LowState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class LowState_(idl.IdlStruct, typename="unitree_go.msg.dds_.LowState_"): + head: types.array[types.uint8, 2] + level_flag: types.uint8 + frame_reserve: types.uint8 + sn: types.array[types.uint32, 2] + version: types.array[types.uint32, 2] + bandwidth: types.uint16 + imu_state: 'unitree_sdk2py.idl.unitree_go.msg.dds_.IMUState_' + motor_state: types.array['unitree_sdk2py.idl.unitree_go.msg.dds_.MotorState_', 20] + bms_state: 'unitree_sdk2py.idl.unitree_go.msg.dds_.BmsState_' + foot_force: types.array[types.int16, 4] + foot_force_est: types.array[types.int16, 4] + tick: types.uint32 + wireless_remote: types.array[types.uint8, 40] + bit_flag: types.uint8 + adc_reel: types.float32 + temperature_ntc1: types.uint8 + temperature_ntc2: types.uint8 + power_v: types.float32 + power_a: types.float32 + fan_frequency: types.array[types.uint16, 4] + reserve: types.uint32 + crc: types.uint32 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorCmd_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorCmd_.py index 5a2dd85..fdf3b6d 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorCmd_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorCmd_.py @@ -1,33 +1,33 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: MotorCmd_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class MotorCmd_(idl.IdlStruct, typename="unitree_go.msg.dds_.MotorCmd_"): - mode: types.uint8 - q: types.float32 - dq: types.float32 - tau: types.float32 - kp: types.float32 - kd: types.float32 - reserve: types.array[types.uint32, 3] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: MotorCmd_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class MotorCmd_(idl.IdlStruct, typename="unitree_go.msg.dds_.MotorCmd_"): + mode: types.uint8 + q: types.float32 + dq: types.float32 + tau: types.float32 + kp: types.float32 + kd: types.float32 + reserve: types.array[types.uint32, 3] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorState_.py index 0787acb..5c560a1 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_MotorState_.py @@ -1,37 +1,37 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: MotorState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class MotorState_(idl.IdlStruct, typename="unitree_go.msg.dds_.MotorState_"): - mode: types.uint8 - q: types.float32 - dq: types.float32 - ddq: types.float32 - tau_est: types.float32 - q_raw: types.float32 - dq_raw: types.float32 - ddq_raw: types.float32 - temperature: types.uint8 - lost: types.uint32 - reserve: types.array[types.uint32, 2] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: MotorState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class MotorState_(idl.IdlStruct, typename="unitree_go.msg.dds_.MotorState_"): + mode: types.uint8 + q: types.float32 + dq: types.float32 + ddq: types.float32 + tau_est: types.float32 + q_raw: types.float32 + dq_raw: types.float32 + ddq_raw: types.float32 + temperature: types.uint8 + lost: types.uint32 + reserve: types.array[types.uint32, 2] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_PathPoint_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_PathPoint_.py index 20a8c55..dfcdbe4 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_PathPoint_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_PathPoint_.py @@ -1,33 +1,33 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: PathPoint_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class PathPoint_(idl.IdlStruct, typename="unitree_go.msg.dds_.PathPoint_"): - t_from_start: types.float32 - x: types.float32 - y: types.float32 - yaw: types.float32 - vx: types.float32 - vy: types.float32 - vyaw: types.float32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: PathPoint_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PathPoint_(idl.IdlStruct, typename="unitree_go.msg.dds_.PathPoint_"): + t_from_start: types.float32 + x: types.float32 + y: types.float32 + yaw: types.float32 + vx: types.float32 + vy: types.float32 + vyaw: types.float32 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Req_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Req_.py index 5bb39b3..88057c4 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Req_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Req_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: Req_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Req_(idl.IdlStruct, typename="unitree_go.msg.dds_.Req_"): - uuid: str - body: str - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: Req_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Req_(idl.IdlStruct, typename="unitree_go.msg.dds_.Req_"): + uuid: str + body: str + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Res_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Res_.py index 684a5a7..5d5eda7 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_Res_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_Res_.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: Res_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class Res_(idl.IdlStruct, typename="unitree_go.msg.dds_.Res_"): - uuid: str - data: types.sequence[types.uint8] - body: str - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: Res_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Res_(idl.IdlStruct, typename="unitree_go.msg.dds_.Res_"): + uuid: str + data: types.sequence[types.uint8] + body: str + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_SportModeState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_SportModeState_.py index e0a26a1..4925ec6 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_SportModeState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_SportModeState_.py @@ -1,42 +1,42 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: SportModeState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class SportModeState_(idl.IdlStruct, typename="unitree_go.msg.dds_.SportModeState_"): - stamp: 'unitree_sdk2py.idl.unitree_go.msg.dds_.TimeSpec_' - error_code: types.uint32 - imu_state: 'unitree_sdk2py.idl.unitree_go.msg.dds_.IMUState_' - mode: types.uint8 - progress: types.float32 - gait_type: types.uint8 - foot_raise_height: types.float32 - position: types.array[types.float32, 3] - body_height: types.float32 - velocity: types.array[types.float32, 3] - yaw_speed: types.float32 - range_obstacle: types.array[types.float32, 4] - foot_force: types.array[types.int16, 4] - foot_position_body: types.array[types.float32, 12] - foot_speed_body: types.array[types.float32, 12] - path_point: types.array['unitree_sdk2py.idl.unitree_go.msg.dds_.PathPoint_', 10] - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: SportModeState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class SportModeState_(idl.IdlStruct, typename="unitree_go.msg.dds_.SportModeState_"): + stamp: 'unitree_sdk2py.idl.unitree_go.msg.dds_.TimeSpec_' + error_code: types.uint32 + imu_state: 'unitree_sdk2py.idl.unitree_go.msg.dds_.IMUState_' + mode: types.uint8 + progress: types.float32 + gait_type: types.uint8 + foot_raise_height: types.float32 + position: types.array[types.float32, 3] + body_height: types.float32 + velocity: types.array[types.float32, 3] + yaw_speed: types.float32 + range_obstacle: types.array[types.float32, 4] + foot_force: types.array[types.int16, 4] + foot_position_body: types.array[types.float32, 12] + foot_speed_body: types.array[types.float32, 12] + path_point: types.array['unitree_sdk2py.idl.unitree_go.msg.dds_.PathPoint_', 10] + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_TimeSpec_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_TimeSpec_.py index 7a580b6..3e312f6 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_TimeSpec_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_TimeSpec_.py @@ -1,28 +1,28 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: TimeSpec_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class TimeSpec_(idl.IdlStruct, typename="unitree_go.msg.dds_.TimeSpec_"): - sec: types.int32 - nanosec: types.uint32 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: TimeSpec_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class TimeSpec_(idl.IdlStruct, typename="unitree_go.msg.dds_.TimeSpec_"): + sec: types.int32 + nanosec: types.uint32 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbState_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbState_.py index d5f2588..96c96ff 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbState_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbState_.py @@ -1,43 +1,43 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: UwbState_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class UwbState_(idl.IdlStruct, typename="unitree_go.msg.dds_.UwbState_"): - version: types.array[types.uint8, 2] - channel: types.uint8 - joy_mode: types.uint8 - orientation_est: types.float32 - pitch_est: types.float32 - distance_est: types.float32 - yaw_est: types.float32 - tag_roll: types.float32 - tag_pitch: types.float32 - tag_yaw: types.float32 - base_roll: types.float32 - base_pitch: types.float32 - base_yaw: types.float32 - joystick: types.array[types.float32, 2] - error_state: types.uint8 - buttons: types.uint8 - enabled_from_app: types.uint8 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: UwbState_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class UwbState_(idl.IdlStruct, typename="unitree_go.msg.dds_.UwbState_"): + version: types.array[types.uint8, 2] + channel: types.uint8 + joy_mode: types.uint8 + orientation_est: types.float32 + pitch_est: types.float32 + distance_est: types.float32 + yaw_est: types.float32 + tag_roll: types.float32 + tag_pitch: types.float32 + tag_yaw: types.float32 + base_roll: types.float32 + base_pitch: types.float32 + base_yaw: types.float32 + joystick: types.array[types.float32, 2] + error_state: types.uint8 + buttons: types.uint8 + enabled_from_app: types.uint8 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbSwitch_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbSwitch_.py index b902ef8..16ca58d 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbSwitch_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_UwbSwitch_.py @@ -1,27 +1,27 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: UwbSwitch_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class UwbSwitch_(idl.IdlStruct, typename="unitree_go.msg.dds_.UwbSwitch_"): - enabled: types.uint8 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: UwbSwitch_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class UwbSwitch_(idl.IdlStruct, typename="unitree_go.msg.dds_.UwbSwitch_"): + enabled: types.uint8 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/_WirelessController_.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/_WirelessController_.py index 18919dd..0432295 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/_WirelessController_.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/_WirelessController_.py @@ -1,31 +1,31 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - IDL file: WirelessController_.idl - -""" - -from enum import auto -from typing import TYPE_CHECKING, Optional -from dataclasses import dataclass - -import cyclonedds.idl as idl -import cyclonedds.idl.annotations as annotate -import cyclonedds.idl.types as types - -# root module import for resolving types -# import unitree_go - - -@dataclass -@annotate.final -@annotate.autoid("sequential") -class WirelessController_(idl.IdlStruct, typename="unitree_go.msg.dds_.WirelessController_"): - lx: types.float32 - ly: types.float32 - rx: types.float32 - ry: types.float32 - keys: types.uint16 - - +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + IDL file: WirelessController_.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +# import unitree_go + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class WirelessController_(idl.IdlStruct, typename="unitree_go.msg.dds_.WirelessController_"): + lx: types.float32 + ly: types.float32 + rx: types.float32 + ry: types.float32 + keys: types.uint16 + + diff --git a/unitree_sdk2py/idl/unitree_go/msg/dds_/__init__.py b/unitree_sdk2py/idl/unitree_go/msg/dds_/__init__.py index e032773..34faa13 100644 --- a/unitree_sdk2py/idl/unitree_go/msg/dds_/__init__.py +++ b/unitree_sdk2py/idl/unitree_go/msg/dds_/__init__.py @@ -1,29 +1,29 @@ -""" - Generated by Eclipse Cyclone DDS idlc Python Backend - Cyclone DDS IDL version: v0.11.0 - Module: unitree_go.msg.dds_ - -""" - -from ._AudioData_ import AudioData_ -from ._BmsCmd_ import BmsCmd_ -from ._BmsState_ import BmsState_ -from ._Error_ import Error_ -from ._Go2FrontVideoData_ import Go2FrontVideoData_ -from ._HeightMap_ import HeightMap_ -from ._IMUState_ import IMUState_ -from ._InterfaceConfig_ import InterfaceConfig_ -from ._LidarState_ import LidarState_ -from ._LowCmd_ import LowCmd_ -from ._LowState_ import LowState_ -from ._MotorCmd_ import MotorCmd_ -from ._MotorState_ import MotorState_ -from ._Req_ import Req_ -from ._Res_ import Res_ -from ._SportModeState_ import SportModeState_ -from ._TimeSpec_ import TimeSpec_ -from ._PathPoint_ import PathPoint_ -from ._UwbState_ import UwbState_ -from ._UwbSwitch_ import UwbSwitch_ -from ._WirelessController_ import WirelessController_ -__all__ = ["AudioData_", "BmsCmd_", "BmsState_", "Error_", "Go2FrontVideoData_", "HeightMap_", "IMUState_", "InterfaceConfig_", "LidarState_", "LowCmd_", "LowState_", "MotorCmd_", "MotorState_", "Req_", "Res_", "SportModeState_", "TimeSpec_", "PathPoint_", "UwbState_", "UwbSwitch_", "WirelessController_", ] +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.11.0 + Module: unitree_go.msg.dds_ + +""" + +from ._AudioData_ import AudioData_ +from ._BmsCmd_ import BmsCmd_ +from ._BmsState_ import BmsState_ +from ._Error_ import Error_ +from ._Go2FrontVideoData_ import Go2FrontVideoData_ +from ._HeightMap_ import HeightMap_ +from ._IMUState_ import IMUState_ +from ._InterfaceConfig_ import InterfaceConfig_ +from ._LidarState_ import LidarState_ +from ._LowCmd_ import LowCmd_ +from ._LowState_ import LowState_ +from ._MotorCmd_ import MotorCmd_ +from ._MotorState_ import MotorState_ +from ._Req_ import Req_ +from ._Res_ import Res_ +from ._SportModeState_ import SportModeState_ +from ._TimeSpec_ import TimeSpec_ +from ._PathPoint_ import PathPoint_ +from ._UwbState_ import UwbState_ +from ._UwbSwitch_ import UwbSwitch_ +from ._WirelessController_ import WirelessController_ +__all__ = ["AudioData_", "BmsCmd_", "BmsState_", "Error_", "Go2FrontVideoData_", "HeightMap_", "IMUState_", "InterfaceConfig_", "LidarState_", "LowCmd_", "LowState_", "MotorCmd_", "MotorState_", "Req_", "Res_", "SportModeState_", "TimeSpec_", "PathPoint_", "UwbState_", "UwbSwitch_", "WirelessController_", ] diff --git a/unitree_sdk2py/rpc/client.py b/unitree_sdk2py/rpc/client.py index d774e53..c4bd19b 100644 --- a/unitree_sdk2py/rpc/client.py +++ b/unitree_sdk2py/rpc/client.py @@ -1,89 +1,89 @@ -from .client_base import ClientBase -from .lease_client import LeaseClient -from .internal import * - -""" -" class Client -""" -class Client(ClientBase): - def __init__(self, serviceName: str, enabaleLease: bool = False): - super().__init__(serviceName) - - self.__apiMapping = {} - self.__apiVersion = None - self.__leaseClient = None - self.__enableLease = enabaleLease - - if (self.__enableLease): - self.__leaseClient = LeaseClient(serviceName) - self.__leaseClient.Init() - - def WaitLeaseApplied(self): - if self.__enableLease: - self.__leaseClient.WaitApplied() - - def GetLeaseId(self): - if self.__enableLease: - return self.__leaseClient.GetId() - else: - return None - - def GetApiVersion(self): - return self.__apiVersion - - def GetServerApiVersion(self): - code, apiVerson = self._CallBase(RPC_API_ID_INTERNAL_API_VERSION, "{}", 0, 0) - if code != 0: - print("[Client] get server api version error:", code) - return code, None - else: - return code, apiVerson - - def _SetApiVerson(self, apiVersion: str): - self.__apiVersion = apiVersion - - def _Call(self, apiId: int, parameter: str): - ret, proirity, leaseId = self.__CheckApi(apiId) - if ret == 0: - return self._CallBase(apiId, parameter, proirity, leaseId) - else: - return RPC_ERR_CLIENT_API_NOT_REG, None - - def _CallNoReply(self, apiId: int, parameter: str): - ret, proirity, leaseId = self.__CheckApi(apiId) - if ret == 0: - return self._CallNoReplyBase(apiId, parameter, proirity, leaseId) - else: - return RPC_ERR_CLIENT_API_NOT_REG - - def _CallBinary(self, apiId: int, parameter: list): - ret, proirity, leaseId = self.__CheckApi(apiId) - if ret == 0: - return self._CallBinaryBase(apiId, parameter, proirity, leaseId) - else: - return RPC_ERR_CLIENT_API_NOT_REG, None - - def _CallBinaryNoReply(self, apiId: int, parameter: list): - ret, proirity, leaseId = self.__CheckApi(apiId) - if ret == 0: - return self._CallBinaryNoReplyBase(apiId, parameter, proirity, leaseId) - else: - return RPC_ERR_CLIENT_API_NOT_REG - - def _RegistApi(self, apiId: int, proirity: int): - self.__apiMapping[apiId] = proirity - - def __CheckApi(self, apiId: int): - proirity = 0 - leaseId = 0 - - if apiId > RPC_INTERNAL_API_ID_MAX: - proirity = self.__apiMapping.get(apiId) - - if proirity is None: - return RPC_ERR_CLIENT_API_NOT_REG, proirity, leaseId - - if self.__enableLease: - leaseId = self.__leaseClient.GetId() - +from .client_base import ClientBase +from .lease_client import LeaseClient +from .internal import * + +""" +" class Client +""" +class Client(ClientBase): + def __init__(self, serviceName: str, enabaleLease: bool = False): + super().__init__(serviceName) + + self.__apiMapping = {} + self.__apiVersion = None + self.__leaseClient = None + self.__enableLease = enabaleLease + + if (self.__enableLease): + self.__leaseClient = LeaseClient(serviceName) + self.__leaseClient.Init() + + def WaitLeaseApplied(self): + if self.__enableLease: + self.__leaseClient.WaitApplied() + + def GetLeaseId(self): + if self.__enableLease: + return self.__leaseClient.GetId() + else: + return None + + def GetApiVersion(self): + return self.__apiVersion + + def GetServerApiVersion(self): + code, apiVerson = self._CallBase(RPC_API_ID_INTERNAL_API_VERSION, "{}", 0, 0) + if code != 0: + print("[Client] get server api version error:", code) + return code, None + else: + return code, apiVerson + + def _SetApiVerson(self, apiVersion: str): + self.__apiVersion = apiVersion + + def _Call(self, apiId: int, parameter: str): + ret, proirity, leaseId = self.__CheckApi(apiId) + if ret == 0: + return self._CallBase(apiId, parameter, proirity, leaseId) + else: + return RPC_ERR_CLIENT_API_NOT_REG, None + + def _CallNoReply(self, apiId: int, parameter: str): + ret, proirity, leaseId = self.__CheckApi(apiId) + if ret == 0: + return self._CallNoReplyBase(apiId, parameter, proirity, leaseId) + else: + return RPC_ERR_CLIENT_API_NOT_REG + + def _CallBinary(self, apiId: int, parameter: list): + ret, proirity, leaseId = self.__CheckApi(apiId) + if ret == 0: + return self._CallBinaryBase(apiId, parameter, proirity, leaseId) + else: + return RPC_ERR_CLIENT_API_NOT_REG, None + + def _CallBinaryNoReply(self, apiId: int, parameter: list): + ret, proirity, leaseId = self.__CheckApi(apiId) + if ret == 0: + return self._CallBinaryNoReplyBase(apiId, parameter, proirity, leaseId) + else: + return RPC_ERR_CLIENT_API_NOT_REG + + def _RegistApi(self, apiId: int, proirity: int): + self.__apiMapping[apiId] = proirity + + def __CheckApi(self, apiId: int): + proirity = 0 + leaseId = 0 + + if apiId > RPC_INTERNAL_API_ID_MAX: + proirity = self.__apiMapping.get(apiId) + + if proirity is None: + return RPC_ERR_CLIENT_API_NOT_REG, proirity, leaseId + + if self.__enableLease: + leaseId = self.__leaseClient.GetId() + return 0, proirity, leaseId \ No newline at end of file diff --git a/unitree_sdk2py/rpc/client_base.py b/unitree_sdk2py/rpc/client_base.py index 1bac028..d3c08e9 100644 --- a/unitree_sdk2py/rpc/client_base.py +++ b/unitree_sdk2py/rpc/client_base.py @@ -1,93 +1,93 @@ -import time - -from ..idl.unitree_api.msg.dds_ import Request_ as Request -from ..idl.unitree_api.msg.dds_ import RequestHeader_ as RequestHeader -from ..idl.unitree_api.msg.dds_ import RequestLease_ as RequestLease -from ..idl.unitree_api.msg.dds_ import RequestIdentity_ as RequestIdentity -from ..idl.unitree_api.msg.dds_ import RequestPolicy_ as RequestPolicy - -from ..utils.future import FutureResult - -from .client_stub import ClientStub -from .internal import * - - -""" -" class ClientBase -""" -class ClientBase: - def __init__(self, serviceName: str): - self.__timeout = 1.0 - self.__stub = ClientStub(serviceName) - self.__stub.Init() - - def SetTimeout(self, timeout: float): - self.__timeout = timeout - - def _CallBase(self, apiId: int, parameter: str, proirity: int = 0, leaseId: int = 0): - # print("[CallBase] call apiId:", apiId, ", proirity:", proirity, ", leaseId:", leaseId) - header = self.__SetHeader(apiId, leaseId, proirity, False) - request = Request(header, parameter, []) - - future = self.__stub.SendRequest(request, self.__timeout) - if future is None: - return RPC_ERR_CLIENT_SEND, None - - result = future.GetResult(self.__timeout) - - if result.code != FutureResult.FUTURE_SUCC: - self.__stub.RemoveFuture(request.header.identity.id) - code = RPC_ERR_CLIENT_API_TIMEOUT if result.code == FutureResult.FUTUTE_ERR_TIMEOUT else RPC_ERR_UNKNOWN - return code, None - - response = result.value - - if response.header.identity.api_id != apiId: - return RPC_ERR_CLIENT_API_NOT_MATCH, None - else: - return response.header.status.code, response.data - - def _CallNoReplyBase(self, apiId: int, parameter: str, proirity: int, leaseId: int): - header = self.__SetHeader(apiId, leaseId, proirity, True) - request = Request(header, parameter, []) - - if self.__stub.Send(request, self.__timeout): - return 0 - else: - return RPC_ERR_CLIENT_SEND - - def _CallBinaryBase(self, apiId: int, parameter: list, proirity: int, leaseId: int): - header = self.__SetHeader(apiId, leaseId, proirity, False) - request = Request(header, "", parameter) - - future = self.__stub.SendRequest(request, self.__timeout) - if future is None: - return RPC_ERR_CLIENT_SEND, None - - result = future.GetResult(self.__timeout) - if result.code != FutureResult.FUTURE_SUCC: - self.__stub.RemoveFuture(request.header.identity.id) - code = RPC_ERR_CLIENT_API_TIMEOUT if result.code == FutureResult.FUTUTE_ERR_TIMEOUT else RPC_ERR_UNKNOWN - return code, None - - response = result.value - - if response.header.identity.api_id != apiId: - return RPC_ERR_CLIENT_API_NOT_MATCH, None - else: - return response.header.status.code, response.binary - - def _CallBinaryNoReplyBase(self, apiId: int, parameter: list, proirity: int, leaseId: int): - header = self.__SetHeader(apiId, leaseId, proirity, True) - request = Request(header, "", parameter) - - if self.__stub.Send(request, self.__timeout): - return 0 - else: - return RPC_ERR_CLIENT_SEND - - def __SetHeader(self, apiId: int, leaseId: int, priority: int, noReply: bool): - identity = RequestIdentity(time.monotonic_ns(), apiId) - lease = RequestLease(leaseId) - policy = RequestPolicy(priority, noReply) - return RequestHeader(identity, lease, policy) +import time + +from ..idl.unitree_api.msg.dds_ import Request_ as Request +from ..idl.unitree_api.msg.dds_ import RequestHeader_ as RequestHeader +from ..idl.unitree_api.msg.dds_ import RequestLease_ as RequestLease +from ..idl.unitree_api.msg.dds_ import RequestIdentity_ as RequestIdentity +from ..idl.unitree_api.msg.dds_ import RequestPolicy_ as RequestPolicy + +from ..utils.future import FutureResult + +from .client_stub import ClientStub +from .internal import * + + +""" +" class ClientBase +""" +class ClientBase: + def __init__(self, serviceName: str): + self.__timeout = 1.0 + self.__stub = ClientStub(serviceName) + self.__stub.Init() + + def SetTimeout(self, timeout: float): + self.__timeout = timeout + + def _CallBase(self, apiId: int, parameter: str, proirity: int = 0, leaseId: int = 0): + # print("[CallBase] call apiId:", apiId, ", proirity:", proirity, ", leaseId:", leaseId) + header = self.__SetHeader(apiId, leaseId, proirity, False) + request = Request(header, parameter, []) + + future = self.__stub.SendRequest(request, self.__timeout) + if future is None: + return RPC_ERR_CLIENT_SEND, None + + result = future.GetResult(self.__timeout) + + if result.code != FutureResult.FUTURE_SUCC: + self.__stub.RemoveFuture(request.header.identity.id) + code = RPC_ERR_CLIENT_API_TIMEOUT if result.code == FutureResult.FUTUTE_ERR_TIMEOUT else RPC_ERR_UNKNOWN + return code, None + + response = result.value + + if response.header.identity.api_id != apiId: + return RPC_ERR_CLIENT_API_NOT_MATCH, None + else: + return response.header.status.code, response.data + + def _CallNoReplyBase(self, apiId: int, parameter: str, proirity: int, leaseId: int): + header = self.__SetHeader(apiId, leaseId, proirity, True) + request = Request(header, parameter, []) + + if self.__stub.Send(request, self.__timeout): + return 0 + else: + return RPC_ERR_CLIENT_SEND + + def _CallBinaryBase(self, apiId: int, parameter: list, proirity: int, leaseId: int): + header = self.__SetHeader(apiId, leaseId, proirity, False) + request = Request(header, "", parameter) + + future = self.__stub.SendRequest(request, self.__timeout) + if future is None: + return RPC_ERR_CLIENT_SEND, None + + result = future.GetResult(self.__timeout) + if result.code != FutureResult.FUTURE_SUCC: + self.__stub.RemoveFuture(request.header.identity.id) + code = RPC_ERR_CLIENT_API_TIMEOUT if result.code == FutureResult.FUTUTE_ERR_TIMEOUT else RPC_ERR_UNKNOWN + return code, None + + response = result.value + + if response.header.identity.api_id != apiId: + return RPC_ERR_CLIENT_API_NOT_MATCH, None + else: + return response.header.status.code, response.binary + + def _CallBinaryNoReplyBase(self, apiId: int, parameter: list, proirity: int, leaseId: int): + header = self.__SetHeader(apiId, leaseId, proirity, True) + request = Request(header, "", parameter) + + if self.__stub.Send(request, self.__timeout): + return 0 + else: + return RPC_ERR_CLIENT_SEND + + def __SetHeader(self, apiId: int, leaseId: int, priority: int, noReply: bool): + identity = RequestIdentity(time.monotonic_ns(), apiId) + lease = RequestLease(leaseId) + policy = RequestPolicy(priority, noReply) + return RequestHeader(identity, lease, policy) diff --git a/unitree_sdk2py/rpc/client_stub.py b/unitree_sdk2py/rpc/client_stub.py index 67c2c8f..d073fce 100644 --- a/unitree_sdk2py/rpc/client_stub.py +++ b/unitree_sdk2py/rpc/client_stub.py @@ -1,69 +1,69 @@ -import time - -from enum import Enum -from threading import Thread, Condition - -from ..idl.unitree_api.msg.dds_ import Request_ as Request -from ..idl.unitree_api.msg.dds_ import Response_ as Response - -from ..core.channel import ChannelFactory -from ..core.channel_name import ChannelType, GetClientChannelName -from .request_future import RequestFuture, RequestFutureQueue - - -""" -" class ClientStub -""" -class ClientStub: - def __init__(self, serviceName: str): - self.__serviceName = serviceName - self.__futureQueue = None - - self.__sendChannel = None - self.__recvChannel = None - - def Init(self): - factory = ChannelFactory() - self.__futureQueue = RequestFutureQueue() - - # create channel - self.__sendChannel = factory.CreateSendChannel(GetClientChannelName(self.__serviceName, ChannelType.SEND), Request) - self.__recvChannel = factory.CreateRecvChannel(GetClientChannelName(self.__serviceName, ChannelType.RECV), Response, - self.__ResponseHandler,10) - time.sleep(0.5) - - - def Send(self, request: Request, timeout: float): - if self.__sendChannel.Write(request, timeout): - return True - else: - print("[ClientStub] send error. id:", request.header.identity.id) - return False - - def SendRequest(self, request: Request, timeout: float): - id = request.header.identity.id - - future = RequestFuture() - future.SetRequestId(id) - self.__futureQueue.Set(id, future) - - if self.__sendChannel.Write(request, timeout): - return future - else: - print("[ClientStub] send request error. id:", request.header.identity.id) - self.__futureQueue.Remove(id) - return None - - def RemoveFuture(self, requestId: int): - self.__futureQueue.Remove(requestId) - - def __ResponseHandler(self, response: Response): - id = response.header.identity.id - # apiId = response.header.identity.api_id - # print("[ClientStub] responseHandler recv response id:", id, ", apiId:", apiId) - future = self.__futureQueue.Get(id) - if future is None: - # print("[ClientStub] get future from queue error. id:", id) - pass - elif not future.Ready(response): - print("[ClientStub] set future ready error.") +import time + +from enum import Enum +from threading import Thread, Condition + +from ..idl.unitree_api.msg.dds_ import Request_ as Request +from ..idl.unitree_api.msg.dds_ import Response_ as Response + +from ..core.channel import ChannelFactory +from ..core.channel_name import ChannelType, GetClientChannelName +from .request_future import RequestFuture, RequestFutureQueue + + +""" +" class ClientStub +""" +class ClientStub: + def __init__(self, serviceName: str): + self.__serviceName = serviceName + self.__futureQueue = None + + self.__sendChannel = None + self.__recvChannel = None + + def Init(self): + factory = ChannelFactory() + self.__futureQueue = RequestFutureQueue() + + # create channel + self.__sendChannel = factory.CreateSendChannel(GetClientChannelName(self.__serviceName, ChannelType.SEND), Request) + self.__recvChannel = factory.CreateRecvChannel(GetClientChannelName(self.__serviceName, ChannelType.RECV), Response, + self.__ResponseHandler,10) + time.sleep(0.5) + + + def Send(self, request: Request, timeout: float): + if self.__sendChannel.Write(request, timeout): + return True + else: + print("[ClientStub] send error. id:", request.header.identity.id) + return False + + def SendRequest(self, request: Request, timeout: float): + id = request.header.identity.id + + future = RequestFuture() + future.SetRequestId(id) + self.__futureQueue.Set(id, future) + + if self.__sendChannel.Write(request, timeout): + return future + else: + print("[ClientStub] send request error. id:", request.header.identity.id) + self.__futureQueue.Remove(id) + return None + + def RemoveFuture(self, requestId: int): + self.__futureQueue.Remove(requestId) + + def __ResponseHandler(self, response: Response): + id = response.header.identity.id + # apiId = response.header.identity.api_id + # print("[ClientStub] responseHandler recv response id:", id, ", apiId:", apiId) + future = self.__futureQueue.Get(id) + if future is None: + # print("[ClientStub] get future from queue error. id:", id) + pass + elif not future.Ready(response): + print("[ClientStub] set future ready error.") diff --git a/unitree_sdk2py/rpc/internal.py b/unitree_sdk2py/rpc/internal.py index 875a78b..423a50a 100644 --- a/unitree_sdk2py/rpc/internal.py +++ b/unitree_sdk2py/rpc/internal.py @@ -1,31 +1,31 @@ -# internal api id max -RPC_INTERNAL_API_ID_MAX = 100 - -# internal api id -RPC_API_ID_INTERNAL_API_VERSION = 1 - -# lease api id -RPC_API_ID_LEASE_APPLY = 101 -RPC_API_ID_LEASE_RENEWAL = 102 - -# lease term default -RPC_LEASE_TERM = 1.0 - -# internal error -RPC_OK = 0 -# client error -RPC_ERR_UNKNOWN = 3001 -RPC_ERR_CLIENT_SEND = 3102 -RPC_ERR_CLIENT_API_NOT_REG = 3103 -RPC_ERR_CLIENT_API_TIMEOUT = 3104 -RPC_ERR_CLIENT_API_NOT_MATCH = 3105 -RPC_ERR_CLIENT_API_DATA = 3106 -RPC_ERR_CLIENT_LEASE_INVALID = 3107 -# server error -RPC_ERR_SERVER_SEND = 3201 -RPC_ERR_SERVER_INTERNAL = 3202 -RPC_ERR_SERVER_API_NOT_IMPL = 3203 -RPC_ERR_SERVER_API_PARAMETER = 3204 -RPC_ERR_SERVER_LEASE_DENIED = 3205 -RPC_ERR_SERVER_LEASE_NOT_EXIST = 3206 -RPC_ERR_SERVER_LEASE_EXIST = 3207 +# internal api id max +RPC_INTERNAL_API_ID_MAX = 100 + +# internal api id +RPC_API_ID_INTERNAL_API_VERSION = 1 + +# lease api id +RPC_API_ID_LEASE_APPLY = 101 +RPC_API_ID_LEASE_RENEWAL = 102 + +# lease term default +RPC_LEASE_TERM = 1.0 + +# internal error +RPC_OK = 0 +# client error +RPC_ERR_UNKNOWN = 3001 +RPC_ERR_CLIENT_SEND = 3102 +RPC_ERR_CLIENT_API_NOT_REG = 3103 +RPC_ERR_CLIENT_API_TIMEOUT = 3104 +RPC_ERR_CLIENT_API_NOT_MATCH = 3105 +RPC_ERR_CLIENT_API_DATA = 3106 +RPC_ERR_CLIENT_LEASE_INVALID = 3107 +# server error +RPC_ERR_SERVER_SEND = 3201 +RPC_ERR_SERVER_INTERNAL = 3202 +RPC_ERR_SERVER_API_NOT_IMPL = 3203 +RPC_ERR_SERVER_API_PARAMETER = 3204 +RPC_ERR_SERVER_LEASE_DENIED = 3205 +RPC_ERR_SERVER_LEASE_NOT_EXIST = 3206 +RPC_ERR_SERVER_LEASE_EXIST = 3207 diff --git a/unitree_sdk2py/rpc/lease_client.py b/unitree_sdk2py/rpc/lease_client.py index 37f600f..0105a6b 100644 --- a/unitree_sdk2py/rpc/lease_client.py +++ b/unitree_sdk2py/rpc/lease_client.py @@ -1,113 +1,113 @@ -import time -import socket -import os -import json - -from threading import Thread, Lock - -from .client_base import ClientBase -from .internal import * - - -""" -" class LeaseContext -""" -class LeaseContext: - def __init__(self): - self.id = 0 - self.term = RPC_LEASE_TERM - - def Update(self, id, term): - self.id = id - self.term = term - - def Reset(self): - self.id = 0 - self.term = RPC_LEASE_TERM - - def Valid(self): - return self.id != 0 - - -""" -" class LeaseClient -""" -class LeaseClient(ClientBase): - def __init__(self, name: str): - self.__name = name + "_lease" - self.__contextName = socket.gethostname() + "/" + name + "/" + str(os.getpid()) - self.__context = LeaseContext() - self.__thread = None - self.__lock = Lock() - super().__init__(self.__name) - print("[LeaseClient] lease name:", self.__name, ", context name:", self.__contextName) - - def Init(self): - self.SetTimeout(1.0) - self.__thread = Thread(target=self.__ThreadFunc, name=self.__name, daemon=True) - self.__thread.start() - - def WaitApplied(self): - while True: - with self.__lock: - if self.__context.Valid(): - break - time.sleep(0.1) - - def GetId(self): - with self.__lock: - return self.__context.id - - def Applied(self): - with self.__lock: - return self.__context.Valid() - - def __Apply(self): - parameter = {} - parameter["name"] = self.__contextName - p = json.dumps(parameter) - - c, d = self._CallBase(RPC_API_ID_LEASE_APPLY, p) - if c != 0: - print("[LeaseClient] apply lease error. code:", c) - return - - data = json.loads(d) - - id = data["id"] - term = data["term"] - - print("[LeaseClient] lease applied id:", id, ", term:", term) - - with self.__lock: - self.__context.Update(id, float(term/1000000)) - - def __Renewal(self): - parameter = {} - p = json.dumps(parameter) - - c, d = self._CallBase(RPC_API_ID_LEASE_RENEWAL, p, 0, self.__context.id) - if c != 0: - print("[LeaseClient] renewal lease error. code:", c) - if c == RPC_ERR_SERVER_LEASE_NOT_EXIST: - with self.__lock: - self.__context.Reset() - - def __GetWaitSec(self): - waitsec = 0.0 - if self.__context.Valid(): - waitsec = self.__context.term - - if waitsec <= 0: - waitsec = RPC_LEASE_TERM - - return waitsec * 0.3 - - def __ThreadFunc(self): - while True: - if self.__context.Valid(): - self.__Renewal() - else: - self.__Apply() - # sleep waitsec - time.sleep(self.__GetWaitSec()) +import time +import socket +import os +import json + +from threading import Thread, Lock + +from .client_base import ClientBase +from .internal import * + + +""" +" class LeaseContext +""" +class LeaseContext: + def __init__(self): + self.id = 0 + self.term = RPC_LEASE_TERM + + def Update(self, id, term): + self.id = id + self.term = term + + def Reset(self): + self.id = 0 + self.term = RPC_LEASE_TERM + + def Valid(self): + return self.id != 0 + + +""" +" class LeaseClient +""" +class LeaseClient(ClientBase): + def __init__(self, name: str): + self.__name = name + "_lease" + self.__contextName = socket.gethostname() + "/" + name + "/" + str(os.getpid()) + self.__context = LeaseContext() + self.__thread = None + self.__lock = Lock() + super().__init__(self.__name) + print("[LeaseClient] lease name:", self.__name, ", context name:", self.__contextName) + + def Init(self): + self.SetTimeout(1.0) + self.__thread = Thread(target=self.__ThreadFunc, name=self.__name, daemon=True) + self.__thread.start() + + def WaitApplied(self): + while True: + with self.__lock: + if self.__context.Valid(): + break + time.sleep(0.1) + + def GetId(self): + with self.__lock: + return self.__context.id + + def Applied(self): + with self.__lock: + return self.__context.Valid() + + def __Apply(self): + parameter = {} + parameter["name"] = self.__contextName + p = json.dumps(parameter) + + c, d = self._CallBase(RPC_API_ID_LEASE_APPLY, p) + if c != 0: + print("[LeaseClient] apply lease error. code:", c) + return + + data = json.loads(d) + + id = data["id"] + term = data["term"] + + print("[LeaseClient] lease applied id:", id, ", term:", term) + + with self.__lock: + self.__context.Update(id, float(term/1000000)) + + def __Renewal(self): + parameter = {} + p = json.dumps(parameter) + + c, d = self._CallBase(RPC_API_ID_LEASE_RENEWAL, p, 0, self.__context.id) + if c != 0: + print("[LeaseClient] renewal lease error. code:", c) + if c == RPC_ERR_SERVER_LEASE_NOT_EXIST: + with self.__lock: + self.__context.Reset() + + def __GetWaitSec(self): + waitsec = 0.0 + if self.__context.Valid(): + waitsec = self.__context.term + + if waitsec <= 0: + waitsec = RPC_LEASE_TERM + + return waitsec * 0.3 + + def __ThreadFunc(self): + while True: + if self.__context.Valid(): + self.__Renewal() + else: + self.__Apply() + # sleep waitsec + time.sleep(self.__GetWaitSec()) diff --git a/unitree_sdk2py/rpc/lease_server.py b/unitree_sdk2py/rpc/lease_server.py index d5b27d1..b2ebaed 100644 --- a/unitree_sdk2py/rpc/lease_server.py +++ b/unitree_sdk2py/rpc/lease_server.py @@ -1,151 +1,151 @@ -import time -import json - -from threading import Lock - -from ..idl.unitree_api.msg.dds_ import Request_ as Request -from ..idl.unitree_api.msg.dds_ import ResponseHeader_ as ResponseHeader -from ..idl.unitree_api.msg.dds_ import ResponseStatus_ as ResponseStatus -from ..idl.unitree_api.msg.dds_ import Response_ as Response - -from .internal import * -from .server_base import ServerBase - - -""" -" class LeaseCache -""" -class LeaseCache: - def __init__(self): - self.lastModified = 0 - self.id = 0 - self.name = None - - def Set(self, id: int, name: str, lastModified: int) : - self.id = id - self.name = name - self.lastModified = lastModified - - def Renewal(self, lastModified: int): - self.lastModified = lastModified - - def Clear(self): - self.id = 0 - self.lastModified = 0 - self.name = None - - -""" -" class LeaseServer -""" -class LeaseServer(ServerBase): - def __init__(self, name: str, term: float): - self.__term = int(term * 1000000) - self.__lock = Lock() - self.__cache = LeaseCache() - super().__init__(name + "_lease") - - def Init(self): - pass - - def Start(self, enablePrioQueue: bool = False): - super()._SetServerRequestHandler(self.__ServerRequestHandler) - super()._Start(enablePrioQueue) - - def CheckRequestLeaseDenied(self, leaseId: int): - with self.__lock: - if self.__cache.id == 0: - return self.__cache.id != leaseId - - now = self.__Now() - if now > self.__cache.lastModified + self.__term: - self.__cache.Clear() - return False - else: - return self.__cache.id != leaseId - - def __Apply(self, parameter: str): - name = "" - data = "" - - try: - p = json.loads(parameter) - name = p.get("name") - - except: - print("[LeaseServer] apply json loads error. parameter:", parameter) - return RPC_ERR_SERVER_API_PARAMETER, data - - if not name: - name = "anonymous" - - id = 0 - lastModified = 0 - setted = False - - now = self.__Now() - - with self.__lock: - id = self.__cache.id - lastModified = self.__cache.lastModified - - if id == 0 or now > lastModified + self.__term: - if id != 0: - print("[LeaseServer] id expired:", id, ", name:", self.__cache.name) - - id = self.__GenerateId() - self.__cache.Set(id, name, now) - setted = True - - print("[LeaseServer] id stored:", id, ", name:", name) - - if setted: - d = {} - d["id"] = id - d["term"] = self.__term - data = json.dumps(d) - return 0, data - else: - return RPC_ERR_SERVER_LEASE_EXIST, data - - - def __Renewal(self, id: int): - now = self.__Now() - - with self.__lock: - if self.__cache.id != id: - return RPC_ERR_SERVER_LEASE_NOT_EXIST - - if now > self.__cache.lastModified + self.__term: - self.__cache.Clear() - return RPC_ERR_SERVER_LEASE_NOT_EXIST - else: - self.__cache.Renewal(now) - return 0 - - def __ServerRequestHandler(self, request: Request): - identity = request.header.identity - parameter = request.parameter - apiId = identity.api_id - code = RPC_ERR_SERVER_API_NOT_IMPL - data = "" - - if apiId == RPC_API_ID_LEASE_APPLY: - code, data = self.__Apply(parameter) - elif apiId == RPC_API_ID_LEASE_RENEWAL: - code = self.__Renewal(request.header.lease.id) - else: - print("[LeaseServer] api is not implemented. apiId", apiId) - - if request.header.policy.noreply: - return - - status = ResponseStatus(code) - response = Response(ResponseHeader(identity, status), data, []) - self._SendResponse(response) - - def __GenerateId(self): - return self.__Now() - - def __Now(self): +import time +import json + +from threading import Lock + +from ..idl.unitree_api.msg.dds_ import Request_ as Request +from ..idl.unitree_api.msg.dds_ import ResponseHeader_ as ResponseHeader +from ..idl.unitree_api.msg.dds_ import ResponseStatus_ as ResponseStatus +from ..idl.unitree_api.msg.dds_ import Response_ as Response + +from .internal import * +from .server_base import ServerBase + + +""" +" class LeaseCache +""" +class LeaseCache: + def __init__(self): + self.lastModified = 0 + self.id = 0 + self.name = None + + def Set(self, id: int, name: str, lastModified: int) : + self.id = id + self.name = name + self.lastModified = lastModified + + def Renewal(self, lastModified: int): + self.lastModified = lastModified + + def Clear(self): + self.id = 0 + self.lastModified = 0 + self.name = None + + +""" +" class LeaseServer +""" +class LeaseServer(ServerBase): + def __init__(self, name: str, term: float): + self.__term = int(term * 1000000) + self.__lock = Lock() + self.__cache = LeaseCache() + super().__init__(name + "_lease") + + def Init(self): + pass + + def Start(self, enablePrioQueue: bool = False): + super()._SetServerRequestHandler(self.__ServerRequestHandler) + super()._Start(enablePrioQueue) + + def CheckRequestLeaseDenied(self, leaseId: int): + with self.__lock: + if self.__cache.id == 0: + return self.__cache.id != leaseId + + now = self.__Now() + if now > self.__cache.lastModified + self.__term: + self.__cache.Clear() + return False + else: + return self.__cache.id != leaseId + + def __Apply(self, parameter: str): + name = "" + data = "" + + try: + p = json.loads(parameter) + name = p.get("name") + + except: + print("[LeaseServer] apply json loads error. parameter:", parameter) + return RPC_ERR_SERVER_API_PARAMETER, data + + if not name: + name = "anonymous" + + id = 0 + lastModified = 0 + setted = False + + now = self.__Now() + + with self.__lock: + id = self.__cache.id + lastModified = self.__cache.lastModified + + if id == 0 or now > lastModified + self.__term: + if id != 0: + print("[LeaseServer] id expired:", id, ", name:", self.__cache.name) + + id = self.__GenerateId() + self.__cache.Set(id, name, now) + setted = True + + print("[LeaseServer] id stored:", id, ", name:", name) + + if setted: + d = {} + d["id"] = id + d["term"] = self.__term + data = json.dumps(d) + return 0, data + else: + return RPC_ERR_SERVER_LEASE_EXIST, data + + + def __Renewal(self, id: int): + now = self.__Now() + + with self.__lock: + if self.__cache.id != id: + return RPC_ERR_SERVER_LEASE_NOT_EXIST + + if now > self.__cache.lastModified + self.__term: + self.__cache.Clear() + return RPC_ERR_SERVER_LEASE_NOT_EXIST + else: + self.__cache.Renewal(now) + return 0 + + def __ServerRequestHandler(self, request: Request): + identity = request.header.identity + parameter = request.parameter + apiId = identity.api_id + code = RPC_ERR_SERVER_API_NOT_IMPL + data = "" + + if apiId == RPC_API_ID_LEASE_APPLY: + code, data = self.__Apply(parameter) + elif apiId == RPC_API_ID_LEASE_RENEWAL: + code = self.__Renewal(request.header.lease.id) + else: + print("[LeaseServer] api is not implemented. apiId", apiId) + + if request.header.policy.noreply: + return + + status = ResponseStatus(code) + response = Response(ResponseHeader(identity, status), data, []) + self._SendResponse(response) + + def __GenerateId(self): + return self.__Now() + + def __Now(self): return int(time.time_ns()/1000) \ No newline at end of file diff --git a/unitree_sdk2py/rpc/request_future.py b/unitree_sdk2py/rpc/request_future.py index 037ab10..b396aa9 100644 --- a/unitree_sdk2py/rpc/request_future.py +++ b/unitree_sdk2py/rpc/request_future.py @@ -1,46 +1,46 @@ -from threading import Condition, Lock -from enum import Enum - -from ..idl.unitree_api.msg.dds_ import Response_ as Response -from ..utils.future import Future, FutureResult - - -""" -" class RequestFuture -""" -class RequestFuture(Future): - def __init__(self): - self.__requestId = None - super().__init__() - - def SetRequestId(self, requestId: int): - self.__requestId = requestId - - def GetRequestId(self): - return self.__requestId - - -class RequestFutureQueue: - def __init__(self): - self.__data = {} - self.__lock = Lock() - - def Set(self, requestId: int, future: RequestFuture): - if future is None: - return False - with self.__lock: - self.__data[requestId] = future - return True - - def Get(self, requestId: int): - future = None - with self.__lock: - future = self.__data.get(requestId) - if future is not None: - self.__data.pop(requestId) - return future - - def Remove(self, requestId: int): - with self.__lock: - if id in self.__data: +from threading import Condition, Lock +from enum import Enum + +from ..idl.unitree_api.msg.dds_ import Response_ as Response +from ..utils.future import Future, FutureResult + + +""" +" class RequestFuture +""" +class RequestFuture(Future): + def __init__(self): + self.__requestId = None + super().__init__() + + def SetRequestId(self, requestId: int): + self.__requestId = requestId + + def GetRequestId(self): + return self.__requestId + + +class RequestFutureQueue: + def __init__(self): + self.__data = {} + self.__lock = Lock() + + def Set(self, requestId: int, future: RequestFuture): + if future is None: + return False + with self.__lock: + self.__data[requestId] = future + return True + + def Get(self, requestId: int): + future = None + with self.__lock: + future = self.__data.get(requestId) + if future is not None: + self.__data.pop(requestId) + return future + + def Remove(self, requestId: int): + with self.__lock: + if id in self.__data: self.__data.pop(requestId) \ No newline at end of file diff --git a/unitree_sdk2py/rpc/server.py b/unitree_sdk2py/rpc/server.py index 4e389a8..d36c956 100644 --- a/unitree_sdk2py/rpc/server.py +++ b/unitree_sdk2py/rpc/server.py @@ -1,122 +1,122 @@ -import time - -from typing import Callable, Any - -from ..idl.unitree_api.msg.dds_ import Request_ as Request -from ..idl.unitree_api.msg.dds_ import ResponseStatus_ as ResponseStatus -from ..idl.unitree_api.msg.dds_ import ResponseHeader_ as ResponseHeader -from ..idl.unitree_api.msg.dds_ import Response_ as Response - -from .server_base import ServerBase -from .lease_server import LeaseServer -from .internal import * - -""" -" class Server -""" -class Server(ServerBase): - def __init__(self, name: str): - self.__apiVersion = "" - self.__apiHandlerMapping = {} - self.__apiBinaryHandlerMapping = {} - self.__apiBinarySet = {} - self.__enableLease = False - self.__leaseServer = None - super().__init__(name) - - def Init(self): - pass - - def StartLease(self, term: float = 1.0): - self.__enableLease = True - self.__leaseServer = LeaseServer(self.GetName(), term) - self.__leaseServer.Init() - self.__leaseServer.Start(False) - - def Start(self, enablePrioQueue: bool = False): - super()._SetServerRequestHandler(self.__ServerRequestHandler) - super()._Start(enablePrioQueue) - - def GetApiVersion(self): - return self.__apiVersion - - def _SetApiVersion(self, apiVersion: str): - self.__apiVersion = apiVersion - print("[Server] set api version:", self.__apiVersion) - - def _RegistHandler(self, apiId: int, handler: Callable, checkLease: bool): - self.__apiHandlerMapping[apiId] = (handler, checkLease) - - def _RegistBinaryHandler(self, apiId: int, handler: Callable, checkLease: bool): - self.__apiBinaryHandlerMapping[apiId] = (handler, checkLease) - self.__apiBinarySet.add(apiId) - - def __GetHandler(self, apiId: int): - if apiId in self.__apiHandlerMapping: - return self.__apiHandlerMapping.get(apiId) - else: - return None, False - - def __GetBinaryHandler(self, apiId: int): - if apiId in self.__apiBinaryHandlerMapping: - return self.__apiBinaryHandlerMapping.get(apiId) - else: - return None, False - - def __IsBinary(self, apiId): - return apiId in self.__apiBinarySet - - def __CheckLeaseDenied(self, leaseId: int): - if (self.__enableLease): - return self.__leaseServer.CheckRequestLeaseDenied(leaseId) - else: - return False - - def __ServerRequestHandler(self, request: Request): - parameter = request.parameter - parameterBinary = request.binary - - identity = request.header.identity - leaseId = request.header.lease.id - apiId = identity.api_id - - code = 0 - data = "" - dataBinary = [] - - if apiId == RPC_API_ID_INTERNAL_API_VERSION: - data = self.__apiVersion - else: - requestHandler = None - binaryRequestHandler = None - checkLease = False - - if self.__IsBinary(apiId): - binaryRequestHandler, checkLease = self.__GetBinaryHandler(apiId) - else: - requestHandler, checkLease = self.__GetHandler(apiId) - - if requestHandler is None and binaryRequestHandler is None: - code = RPC_ERR_SERVER_API_NOT_IMPL - elif checkLease and self.__CheckLeaseDenied(leaseId): - code = RPC_ERR_SERVER_LEASE_DENIED - else: - try: - if binaryRequestHandler is None: - code, data = requestHandler(parameter) - if code != 0: - data = "" - else: - code, dataBinary = binaryRequestHandler(parameterBinary) - if code != 0: - dataBinary = [] - except: - code = RPC_ERR_SERVER_INTERNAL - - if request.header.policy.noreply: - return - - status = ResponseStatus(code) - response = Response(ResponseHeader(identity, status), data, dataBinary) - +import time + +from typing import Callable, Any + +from ..idl.unitree_api.msg.dds_ import Request_ as Request +from ..idl.unitree_api.msg.dds_ import ResponseStatus_ as ResponseStatus +from ..idl.unitree_api.msg.dds_ import ResponseHeader_ as ResponseHeader +from ..idl.unitree_api.msg.dds_ import Response_ as Response + +from .server_base import ServerBase +from .lease_server import LeaseServer +from .internal import * + +""" +" class Server +""" +class Server(ServerBase): + def __init__(self, name: str): + self.__apiVersion = "" + self.__apiHandlerMapping = {} + self.__apiBinaryHandlerMapping = {} + self.__apiBinarySet = {} + self.__enableLease = False + self.__leaseServer = None + super().__init__(name) + + def Init(self): + pass + + def StartLease(self, term: float = 1.0): + self.__enableLease = True + self.__leaseServer = LeaseServer(self.GetName(), term) + self.__leaseServer.Init() + self.__leaseServer.Start(False) + + def Start(self, enablePrioQueue: bool = False): + super()._SetServerRequestHandler(self.__ServerRequestHandler) + super()._Start(enablePrioQueue) + + def GetApiVersion(self): + return self.__apiVersion + + def _SetApiVersion(self, apiVersion: str): + self.__apiVersion = apiVersion + print("[Server] set api version:", self.__apiVersion) + + def _RegistHandler(self, apiId: int, handler: Callable, checkLease: bool): + self.__apiHandlerMapping[apiId] = (handler, checkLease) + + def _RegistBinaryHandler(self, apiId: int, handler: Callable, checkLease: bool): + self.__apiBinaryHandlerMapping[apiId] = (handler, checkLease) + self.__apiBinarySet.add(apiId) + + def __GetHandler(self, apiId: int): + if apiId in self.__apiHandlerMapping: + return self.__apiHandlerMapping.get(apiId) + else: + return None, False + + def __GetBinaryHandler(self, apiId: int): + if apiId in self.__apiBinaryHandlerMapping: + return self.__apiBinaryHandlerMapping.get(apiId) + else: + return None, False + + def __IsBinary(self, apiId): + return apiId in self.__apiBinarySet + + def __CheckLeaseDenied(self, leaseId: int): + if (self.__enableLease): + return self.__leaseServer.CheckRequestLeaseDenied(leaseId) + else: + return False + + def __ServerRequestHandler(self, request: Request): + parameter = request.parameter + parameterBinary = request.binary + + identity = request.header.identity + leaseId = request.header.lease.id + apiId = identity.api_id + + code = 0 + data = "" + dataBinary = [] + + if apiId == RPC_API_ID_INTERNAL_API_VERSION: + data = self.__apiVersion + else: + requestHandler = None + binaryRequestHandler = None + checkLease = False + + if self.__IsBinary(apiId): + binaryRequestHandler, checkLease = self.__GetBinaryHandler(apiId) + else: + requestHandler, checkLease = self.__GetHandler(apiId) + + if requestHandler is None and binaryRequestHandler is None: + code = RPC_ERR_SERVER_API_NOT_IMPL + elif checkLease and self.__CheckLeaseDenied(leaseId): + code = RPC_ERR_SERVER_LEASE_DENIED + else: + try: + if binaryRequestHandler is None: + code, data = requestHandler(parameter) + if code != 0: + data = "" + else: + code, dataBinary = binaryRequestHandler(parameterBinary) + if code != 0: + dataBinary = [] + except: + code = RPC_ERR_SERVER_INTERNAL + + if request.header.policy.noreply: + return + + status = ResponseStatus(code) + response = Response(ResponseHeader(identity, status), data, dataBinary) + self._SendResponse(response) \ No newline at end of file diff --git a/unitree_sdk2py/rpc/server_base.py b/unitree_sdk2py/rpc/server_base.py index f010561..d8ddc1c 100644 --- a/unitree_sdk2py/rpc/server_base.py +++ b/unitree_sdk2py/rpc/server_base.py @@ -1,32 +1,32 @@ -import time - -from typing import Callable, Any - -from ..idl.unitree_api.msg.dds_ import Request_ as Request -from ..idl.unitree_api.msg.dds_ import Response_ as Response - -from .server_stub import ServerStub - - -""" -" class ServerBase -""" -class ServerBase: - def __init__(self, name: str): - self.__name = name - self.__serverRequestHandler = None - self.__serverStub = ServerStub(self.__name) - - def GetName(self): - return self.__name - - def _Start(self, enablePrioQueue: bool = False): - self.__serverStub.Init(self.__serverRequestHandler, enablePrioQueue) - print("[ServerBase] server started. name:", self.__name, ", enable proirity queue:", enablePrioQueue) - - def _SetServerRequestHandler(self, serverRequestHandler: Callable): - self.__serverRequestHandler = serverRequestHandler - - def _SendResponse(self, response: Response): - if not self.__serverStub.Send(response, 1.0): - print("[ServerBase] send response error.") +import time + +from typing import Callable, Any + +from ..idl.unitree_api.msg.dds_ import Request_ as Request +from ..idl.unitree_api.msg.dds_ import Response_ as Response + +from .server_stub import ServerStub + + +""" +" class ServerBase +""" +class ServerBase: + def __init__(self, name: str): + self.__name = name + self.__serverRequestHandler = None + self.__serverStub = ServerStub(self.__name) + + def GetName(self): + return self.__name + + def _Start(self, enablePrioQueue: bool = False): + self.__serverStub.Init(self.__serverRequestHandler, enablePrioQueue) + print("[ServerBase] server started. name:", self.__name, ", enable proirity queue:", enablePrioQueue) + + def _SetServerRequestHandler(self, serverRequestHandler: Callable): + self.__serverRequestHandler = serverRequestHandler + + def _SendResponse(self, response: Response): + if not self.__serverStub.Send(response, 1.0): + print("[ServerBase] send response error.") diff --git a/unitree_sdk2py/rpc/server_stub.py b/unitree_sdk2py/rpc/server_stub.py index e67be1f..ec012de 100644 --- a/unitree_sdk2py/rpc/server_stub.py +++ b/unitree_sdk2py/rpc/server_stub.py @@ -1,78 +1,78 @@ -import time - -from enum import Enum -from threading import Thread, Condition -from typing import Callable, Any - -from ..utils.bqueue import BQueue -from ..idl.unitree_api.msg.dds_ import Request_ as Request -from ..idl.unitree_api.msg.dds_ import Response_ as Response - -from ..core.channel import ChannelFactory -from ..core.channel_name import ChannelType, GetServerChannelName - - -""" -" class ServerStub -""" -class ServerStub: - def __init__(self, serviceName: str): - self.__serviceName = serviceName - self.__serverRquestHandler = None - self.__sendChannel = None - self.__recvChannel = None - self.__enablePriority = None - self.__queue = None - self.__prioQueue = None - self.__queueThread = None - self.__prioQueueThread = None - - def Init(self, serverRequestHander: Callable, enablePriority: bool = False): - self.__serverRquestHandler = serverRequestHander - self.__enablePriority = enablePriority - - factory = ChannelFactory() - - # create channel - self.__sendChannel = factory.CreateSendChannel(GetServerChannelName(self.__serviceName, ChannelType.SEND), Response) - self.__recvChannel = factory.CreateRecvChannel(GetServerChannelName(self.__serviceName, ChannelType.RECV), Request, self.__Enqueue, 10) - - # start priority request thread - self.__queue = BQueue(10) - self.__queueThread = Thread(target=self.__QueueThreadFunc, name="server_queue", daemon=True) - self.__queueThread.start() - - if enablePriority: - self.__prioQueue = BQueue(5) - self.__prioQueueThread = Thread(target=self.__PrioQueueThreadFunc, name="server_prio_queue", daemon=True) - self.__prioQueueThread.start() - - # wait thread started - time.sleep(0.5) - - def Send(self, response: Response, timeout: float): - if self.__sendChannel.Write(response, timeout): - return True - else: - print("[ServerStub] send error. id:", response.header.identity.id) - return False - - def __Enqueue(self, request: Request): - if self.__enablePriority and request.header.policy.priority > 0: - self.__prioQueue.Put(request, True) - else: - self.__queue.Put(request, True) - - def __QueueThreadFunc(self): - while True: - request = self.__queue.Get() - if request is None: - continue - self.__serverRquestHandler(request) - - def __PrioQueueThreadFunc(self): - while True: - request = self.__prioQueue.Get() - if request is None: - continue - self.__serverRquestHandler(request) +import time + +from enum import Enum +from threading import Thread, Condition +from typing import Callable, Any + +from ..utils.bqueue import BQueue +from ..idl.unitree_api.msg.dds_ import Request_ as Request +from ..idl.unitree_api.msg.dds_ import Response_ as Response + +from ..core.channel import ChannelFactory +from ..core.channel_name import ChannelType, GetServerChannelName + + +""" +" class ServerStub +""" +class ServerStub: + def __init__(self, serviceName: str): + self.__serviceName = serviceName + self.__serverRquestHandler = None + self.__sendChannel = None + self.__recvChannel = None + self.__enablePriority = None + self.__queue = None + self.__prioQueue = None + self.__queueThread = None + self.__prioQueueThread = None + + def Init(self, serverRequestHander: Callable, enablePriority: bool = False): + self.__serverRquestHandler = serverRequestHander + self.__enablePriority = enablePriority + + factory = ChannelFactory() + + # create channel + self.__sendChannel = factory.CreateSendChannel(GetServerChannelName(self.__serviceName, ChannelType.SEND), Response) + self.__recvChannel = factory.CreateRecvChannel(GetServerChannelName(self.__serviceName, ChannelType.RECV), Request, self.__Enqueue, 10) + + # start priority request thread + self.__queue = BQueue(10) + self.__queueThread = Thread(target=self.__QueueThreadFunc, name="server_queue", daemon=True) + self.__queueThread.start() + + if enablePriority: + self.__prioQueue = BQueue(5) + self.__prioQueueThread = Thread(target=self.__PrioQueueThreadFunc, name="server_prio_queue", daemon=True) + self.__prioQueueThread.start() + + # wait thread started + time.sleep(0.5) + + def Send(self, response: Response, timeout: float): + if self.__sendChannel.Write(response, timeout): + return True + else: + print("[ServerStub] send error. id:", response.header.identity.id) + return False + + def __Enqueue(self, request: Request): + if self.__enablePriority and request.header.policy.priority > 0: + self.__prioQueue.Put(request, True) + else: + self.__queue.Put(request, True) + + def __QueueThreadFunc(self): + while True: + request = self.__queue.Get() + if request is None: + continue + self.__serverRquestHandler(request) + + def __PrioQueueThreadFunc(self): + while True: + request = self.__prioQueue.Get() + if request is None: + continue + self.__serverRquestHandler(request) diff --git a/unitree_sdk2py/test/client/obstacles_avoid_client_example.py b/unitree_sdk2py/test/client/obstacles_avoid_client_example.py index 7936fe7..7ffd7f7 100644 --- a/unitree_sdk2py/test/client/obstacles_avoid_client_example.py +++ b/unitree_sdk2py/test/client/obstacles_avoid_client_example.py @@ -1,91 +1,91 @@ -import time -import os - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.obstacles_avoid.obstacles_avoid_client import ObstaclesAvoidClient - -if __name__ == "__main__": - ChannelFactoryInitialize(0, "enp3s0") - - client = ObstaclesAvoidClient() - client.SetTimeout(3.0) - client.Init() - - while True: - print("##################GetServerApiVersion###################") - code, serverAPiVersion = client.GetServerApiVersion() - if code != 0: - print("get server api error. code:", code) - else: - print("get server api version:", serverAPiVersion) - - if serverAPiVersion != client.GetApiVersion(): - print("api version not equal.") - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable) - - time.sleep(3) - - print("##################SwitchSet (on)###################") - code = client.SwitchSet(True) - if code != 0: - print("switch set error. code:", code) - else: - print("switch set success.") - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable1 = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable1) - - time.sleep(3) - - print("##################SwitchSet (off)###################") - code = client.SwitchSet(False) - if code != 0: - print("switch set error. code:", code) - else: - print("switch set success.") - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable1 = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable1) - - time.sleep(3) - - - print("##################SwitchSet (enable)###################") - - code = client.SwitchSet(enable) - if code != 0: - print("switch set error. code:", code) - else: - print("switch set success. enable:", enable) - - time.sleep(3) - - print("##################SwitchGet###################") - code, enable = client.SwitchGet() - if code != 0: - print("switch get error. code:", code) - else: - print("switch get success. enable:", enable) - - time.sleep(3) +import time +import os + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.obstacles_avoid.obstacles_avoid_client import ObstaclesAvoidClient + +if __name__ == "__main__": + ChannelFactoryInitialize(0, "enp3s0") + + client = ObstaclesAvoidClient() + client.SetTimeout(3.0) + client.Init() + + while True: + print("##################GetServerApiVersion###################") + code, serverAPiVersion = client.GetServerApiVersion() + if code != 0: + print("get server api error. code:", code) + else: + print("get server api version:", serverAPiVersion) + + if serverAPiVersion != client.GetApiVersion(): + print("api version not equal.") + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable) + + time.sleep(3) + + print("##################SwitchSet (on)###################") + code = client.SwitchSet(True) + if code != 0: + print("switch set error. code:", code) + else: + print("switch set success.") + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable1 = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable1) + + time.sleep(3) + + print("##################SwitchSet (off)###################") + code = client.SwitchSet(False) + if code != 0: + print("switch set error. code:", code) + else: + print("switch set success.") + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable1 = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable1) + + time.sleep(3) + + + print("##################SwitchSet (enable)###################") + + code = client.SwitchSet(enable) + if code != 0: + print("switch set error. code:", code) + else: + print("switch set success. enable:", enable) + + time.sleep(3) + + print("##################SwitchGet###################") + code, enable = client.SwitchGet() + if code != 0: + print("switch get error. code:", code) + else: + print("switch get success. enable:", enable) + + time.sleep(3) \ No newline at end of file diff --git a/unitree_sdk2py/test/client/robot_service_client_example.py b/unitree_sdk2py/test/client/robot_service_client_example.py index 01467c0..e2f2054 100644 --- a/unitree_sdk2py/test/client/robot_service_client_example.py +++ b/unitree_sdk2py/test/client/robot_service_client_example.py @@ -1,50 +1,50 @@ -import time -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.robot_state.robot_state_client import RobotStateClient - -if __name__ == "__main__": - ChannelFactoryInitialize(0, "enx000ec6768747") - rsc = RobotStateClient() - rsc.SetTimeout(3.0) - rsc.Init() - - while True: - print("##################GetServerApiVersion###################") - code, serverAPiVersion = rsc.GetServerApiVersion() - - if code != 0: - print("get server api error. code:", code) - else: - print("get server api version:", serverAPiVersion) - - time.sleep(3) - - print("##################ServiceList###################") - code, lst = rsc.ServiceList() - - if code != 0: - print("list sevrice error. code:", code) - else: - print("list service success. len:", len(lst)) - for s in lst: - print("name:", s.name, ", protect:", s.protect, ", status:", s.status) - - time.sleep(3) - - print("##################ServiceSwitch###################") - code = rsc.ServiceSwitch("sport_mode", False) - if code != 0: - print("service stop sport_mode error. code:", code) - else: - print("service stop sport_mode success. code:", code) - - time.sleep(1) - - code = rsc.ServiceSwitch("sport_mode", True) - if code != 0: - print("service start sport_mode error. code:", code) - else: - print("service start sport_mode success. code:", code) - - time.sleep(3) - +import time +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.robot_state.robot_state_client import RobotStateClient + +if __name__ == "__main__": + ChannelFactoryInitialize(0, "enx000ec6768747") + rsc = RobotStateClient() + rsc.SetTimeout(3.0) + rsc.Init() + + while True: + print("##################GetServerApiVersion###################") + code, serverAPiVersion = rsc.GetServerApiVersion() + + if code != 0: + print("get server api error. code:", code) + else: + print("get server api version:", serverAPiVersion) + + time.sleep(3) + + print("##################ServiceList###################") + code, lst = rsc.ServiceList() + + if code != 0: + print("list sevrice error. code:", code) + else: + print("list service success. len:", len(lst)) + for s in lst: + print("name:", s.name, ", protect:", s.protect, ", status:", s.status) + + time.sleep(3) + + print("##################ServiceSwitch###################") + code = rsc.ServiceSwitch("sport_mode", False) + if code != 0: + print("service stop sport_mode error. code:", code) + else: + print("service stop sport_mode success. code:", code) + + time.sleep(1) + + code = rsc.ServiceSwitch("sport_mode", True) + if code != 0: + print("service start sport_mode error. code:", code) + else: + print("service start sport_mode success. code:", code) + + time.sleep(3) + diff --git a/unitree_sdk2py/test/client/sport_client_example.py b/unitree_sdk2py/test/client/sport_client_example.py index 22a8de0..5787cba 100644 --- a/unitree_sdk2py/test/client/sport_client_example.py +++ b/unitree_sdk2py/test/client/sport_client_example.py @@ -1,109 +1,109 @@ -import time -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.sport.sport_client import SportClient, PathPoint, SPORT_PATH_POINT_SIZE - -if __name__ == "__main__": - ChannelFactoryInitialize(0, "enp2s0") - client = SportClient() - client.SetTimeout(10.0) - client.Init() - - print("##################GetServerApiVersion###################") - code, serverAPiVersion = client.GetServerApiVersion() - if code != 0: - print("get server api error. code:", code) - else: - print("get server api version:", serverAPiVersion) - - if serverAPiVersion != client.GetApiVersion(): - print("api version not equal.") - - time.sleep(3) - - print("##################Trigger###################") - code = client.Trigger() - if code != 0: - print("sport trigger error. code:", code) - else: - print("sport trigger success.") - - time.sleep(3) - - while True: - print("##################RecoveryStand###################") - code = client.RecoveryStand() - - if code != 0: - print("sport recovery stand error. code:", code) - else: - print("sport recovery stand success.") - - time.sleep(3) - - print("##################StandDown###################") - code = client.StandDown() - if code != 0: - print("sport stand down error. code:", code) - else: - print("sport stand down success.") - - time.sleep(3) - - print("##################Damp###################") - code = client.Damp() - if code != 0: - print("sport damp error. code:", code) - else: - print("sport damp down success.") - - time.sleep(3) - - print("##################RecoveryStand###################") - code = client.RecoveryStand() - - if code != 0: - print("sport recovery stand error. code:", code) - else: - print("sport recovery stand success.") - - time.sleep(3) - - print("##################Sit###################") - code = client.Sit() - if code != 0: - print("sport stand down error. code:", code) - else: - print("sport stand down success.") - - time.sleep(3) - - print("##################RiseSit###################") - code = client.RiseSit() - - if code != 0: - print("sport rise sit error. code:", code) - else: - print("sport rise sit success.") - - time.sleep(3) - - print("##################SetBodyHight###################") - code = client.BodyHeight(0.18) - - if code != 0: - print("sport body hight error. code:", code) - else: - print("sport body hight success.") - - time.sleep(3) - - print("##################GetState#################") - keys = ["state", "bodyHeight", "footRaiseHeight", "speedLevel", "gait"] - code, data = client.GetState(keys) - - if code != 0: - print("sport get state error. code:", code) - else: - print("sport get state success. data:", data) - - time.sleep(3) +import time +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.sport.sport_client import SportClient, PathPoint, SPORT_PATH_POINT_SIZE + +if __name__ == "__main__": + ChannelFactoryInitialize(0, "enp2s0") + client = SportClient() + client.SetTimeout(10.0) + client.Init() + + print("##################GetServerApiVersion###################") + code, serverAPiVersion = client.GetServerApiVersion() + if code != 0: + print("get server api error. code:", code) + else: + print("get server api version:", serverAPiVersion) + + if serverAPiVersion != client.GetApiVersion(): + print("api version not equal.") + + time.sleep(3) + + print("##################Trigger###################") + code = client.Trigger() + if code != 0: + print("sport trigger error. code:", code) + else: + print("sport trigger success.") + + time.sleep(3) + + while True: + print("##################RecoveryStand###################") + code = client.RecoveryStand() + + if code != 0: + print("sport recovery stand error. code:", code) + else: + print("sport recovery stand success.") + + time.sleep(3) + + print("##################StandDown###################") + code = client.StandDown() + if code != 0: + print("sport stand down error. code:", code) + else: + print("sport stand down success.") + + time.sleep(3) + + print("##################Damp###################") + code = client.Damp() + if code != 0: + print("sport damp error. code:", code) + else: + print("sport damp down success.") + + time.sleep(3) + + print("##################RecoveryStand###################") + code = client.RecoveryStand() + + if code != 0: + print("sport recovery stand error. code:", code) + else: + print("sport recovery stand success.") + + time.sleep(3) + + print("##################Sit###################") + code = client.Sit() + if code != 0: + print("sport stand down error. code:", code) + else: + print("sport stand down success.") + + time.sleep(3) + + print("##################RiseSit###################") + code = client.RiseSit() + + if code != 0: + print("sport rise sit error. code:", code) + else: + print("sport rise sit success.") + + time.sleep(3) + + print("##################SetBodyHight###################") + code = client.BodyHeight(0.18) + + if code != 0: + print("sport body hight error. code:", code) + else: + print("sport body hight success.") + + time.sleep(3) + + print("##################GetState#################") + keys = ["state", "bodyHeight", "footRaiseHeight", "speedLevel", "gait"] + code, data = client.GetState(keys) + + if code != 0: + print("sport get state error. code:", code) + else: + print("sport get state success. data:", data) + + time.sleep(3) diff --git a/unitree_sdk2py/test/client/video_client_example.py b/unitree_sdk2py/test/client/video_client_example.py index 7eec949..43d554b 100644 --- a/unitree_sdk2py/test/client/video_client_example.py +++ b/unitree_sdk2py/test/client/video_client_example.py @@ -1,26 +1,26 @@ -import time -import os - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.video.video_client import VideoClient - -if __name__ == "__main__": - ChannelFactoryInitialize(0, "enp2s0") - - client = VideoClient() - client.SetTimeout(3.0) - client.Init() - - print("##################GetImageSample###################") - code, data = client.GetImageSample() - - if code != 0: - print("get image sample error. code:", code) - else: - imageName = os.path.dirname(__file__) + time.strftime('/%Y%m%d%H%M%S.jpg',time.localtime()) - print("ImageName:", imageName) - - with open(imageName, "+wb") as f: - f.write(bytes(data)) - - time.sleep(1) +import time +import os + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.video.video_client import VideoClient + +if __name__ == "__main__": + ChannelFactoryInitialize(0, "enp2s0") + + client = VideoClient() + client.SetTimeout(3.0) + client.Init() + + print("##################GetImageSample###################") + code, data = client.GetImageSample() + + if code != 0: + print("get image sample error. code:", code) + else: + imageName = os.path.dirname(__file__) + time.strftime('/%Y%m%d%H%M%S.jpg',time.localtime()) + print("ImageName:", imageName) + + with open(imageName, "+wb") as f: + f.write(bytes(data)) + + time.sleep(1) diff --git a/unitree_sdk2py/test/client/vui_client_example.py b/unitree_sdk2py/test/client/vui_client_example.py index 6df7c09..1678edc 100644 --- a/unitree_sdk2py/test/client/vui_client_example.py +++ b/unitree_sdk2py/test/client/vui_client_example.py @@ -1,74 +1,74 @@ -import time -import os - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.go2.vui.vui_client import VuiClient - -if __name__ == "__main__": - ChannelFactoryInitialize(0, "enp2s0") - - client = VuiClient() - client.SetTimeout(3.0) - client.Init() - - for i in range(1, 11): - print("#################GetBrightness####################") - code, level = client.GetBrightness() - - if code != 0: - print("get brightness error. code:", code) - else: - print("get brightness success. level:", level) - - time.sleep(1) - - print("#################SetBrightness####################") - - code = client.SetBrightness(i) - - if code != 0: - print("set brightness error. code:", code) - else: - print("set brightness success. level:", i) - - time.sleep(1) - - print("#################SetBrightness 0####################") - - code = client.SetBrightness(0) - - if code != 0: - print("set brightness error. code:", code) - else: - print("set brightness 0 success.") - - for i in range(1, 11): - print("#################GetVolume####################") - code, level = client.GetVolume() - - if code != 0: - print("get volume error. code:", code) - else: - print("get volume success. level:", level) - - time.sleep(1) - - print("#################SetVolume####################") - - code = client.SetVolume(i) - - if code != 0: - print("set volume error. code:", code) - else: - print("set volume success. level:", i) - - time.sleep(1) - - print("#################SetVolume 0####################") - - code = client.SetVolume(0) - - if code != 0: - print("set volume error. code:", code) - else: - print("set volume 0 success.") +import time +import os + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.go2.vui.vui_client import VuiClient + +if __name__ == "__main__": + ChannelFactoryInitialize(0, "enp2s0") + + client = VuiClient() + client.SetTimeout(3.0) + client.Init() + + for i in range(1, 11): + print("#################GetBrightness####################") + code, level = client.GetBrightness() + + if code != 0: + print("get brightness error. code:", code) + else: + print("get brightness success. level:", level) + + time.sleep(1) + + print("#################SetBrightness####################") + + code = client.SetBrightness(i) + + if code != 0: + print("set brightness error. code:", code) + else: + print("set brightness success. level:", i) + + time.sleep(1) + + print("#################SetBrightness 0####################") + + code = client.SetBrightness(0) + + if code != 0: + print("set brightness error. code:", code) + else: + print("set brightness 0 success.") + + for i in range(1, 11): + print("#################GetVolume####################") + code, level = client.GetVolume() + + if code != 0: + print("get volume error. code:", code) + else: + print("get volume success. level:", level) + + time.sleep(1) + + print("#################SetVolume####################") + + code = client.SetVolume(i) + + if code != 0: + print("set volume error. code:", code) + else: + print("set volume success. level:", i) + + time.sleep(1) + + print("#################SetVolume 0####################") + + code = client.SetVolume(0) + + if code != 0: + print("set volume error. code:", code) + else: + print("set volume 0 success.") diff --git a/unitree_sdk2py/test/crc/test_crc.py b/unitree_sdk2py/test/crc/test_crc.py index 67d2b7d..590d9aa 100644 --- a/unitree_sdk2py/test/crc/test_crc.py +++ b/unitree_sdk2py/test/crc/test_crc.py @@ -1,15 +1,15 @@ -from unitree_sdk2py.idl.default import * -from unitree_sdk2py.utils.crc import CRC - -crc = CRC() - -""" -" LowCmd CRC -""" -cmd = unitree_go_msg_dds__LowCmd_() -cmd.crc = crc.Crc(cmd) - -state = unitree_go_msg_dds__LowState_() -state.crc = crc.Crc(state) - -print("CRC[LowCmd, LowState]: {}, {}".format(cmd.crc, state.crc)) +from unitree_sdk2py.idl.default import * +from unitree_sdk2py.utils.crc import CRC + +crc = CRC() + +""" +" LowCmd CRC +""" +cmd = unitree_go_msg_dds__LowCmd_() +cmd.crc = crc.Crc(cmd) + +state = unitree_go_msg_dds__LowState_() +state.crc = crc.Crc(state) + +print("CRC[LowCmd, LowState]: {}, {}".format(cmd.crc, state.crc)) diff --git a/unitree_sdk2py/test/helloworld/helloworld.py b/unitree_sdk2py/test/helloworld/helloworld.py index 7e93803..77aacd8 100644 --- a/unitree_sdk2py/test/helloworld/helloworld.py +++ b/unitree_sdk2py/test/helloworld/helloworld.py @@ -1,6 +1,6 @@ -from dataclasses import dataclass -from cyclonedds.idl import IdlStruct - -@dataclass -class HelloWorld(IdlStruct, typename="HelloWorld"): +from dataclasses import dataclass +from cyclonedds.idl import IdlStruct + +@dataclass +class HelloWorld(IdlStruct, typename="HelloWorld"): data: str \ No newline at end of file diff --git a/unitree_sdk2py/test/helloworld/publisher.py b/unitree_sdk2py/test/helloworld/publisher.py index 36e8fb8..6ad3f7a 100644 --- a/unitree_sdk2py/test/helloworld/publisher.py +++ b/unitree_sdk2py/test/helloworld/publisher.py @@ -1,22 +1,22 @@ -import time - -from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize -from helloworld import HelloWorld - -ChannelFactoryInitialize() - -pub = ChannelPublisher("topic", HelloWorld) -pub.Init() - -for i in range(30): - msg = HelloWorld("Hello world. time:" + str(time.time())) - # msg.data = "Hello world. time:" + str(time.time()) - - if pub.Write(msg, 0.5): - print("publish success. msg:", msg) - else: - print("publish error.") - - time.sleep(1) - +import time + +from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize +from helloworld import HelloWorld + +ChannelFactoryInitialize() + +pub = ChannelPublisher("topic", HelloWorld) +pub.Init() + +for i in range(30): + msg = HelloWorld("Hello world. time:" + str(time.time())) + # msg.data = "Hello world. time:" + str(time.time()) + + if pub.Write(msg, 0.5): + print("publish success. msg:", msg) + else: + print("publish error.") + + time.sleep(1) + pub.Close() \ No newline at end of file diff --git a/unitree_sdk2py/test/helloworld/subscriber.py b/unitree_sdk2py/test/helloworld/subscriber.py index 38e4763..7cab080 100644 --- a/unitree_sdk2py/test/helloworld/subscriber.py +++ b/unitree_sdk2py/test/helloworld/subscriber.py @@ -1,19 +1,19 @@ -import time - -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from helloworld import HelloWorld - -ChannelFactoryInitialize() - -sub = ChannelSubscriber("topic", HelloWorld) -sub.Init() - -while True: - msg = sub.Read() - - if msg is None: - print("subscribe error.") - else: - print("subscribe success. msg:", msg) - +import time + +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from helloworld import HelloWorld + +ChannelFactoryInitialize() + +sub = ChannelSubscriber("topic", HelloWorld) +sub.Init() + +while True: + msg = sub.Read() + + if msg is None: + print("subscribe error.") + else: + print("subscribe success. msg:", msg) + pub.Close() \ No newline at end of file diff --git a/unitree_sdk2py/test/lowlevel/lowlevel_control.py b/unitree_sdk2py/test/lowlevel/lowlevel_control.py index 8e94fe1..d8979a9 100644 --- a/unitree_sdk2py/test/lowlevel/lowlevel_control.py +++ b/unitree_sdk2py/test/lowlevel/lowlevel_control.py @@ -1,51 +1,51 @@ -import time - -from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowCmd_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowCmd_ -from unitree_sdk2py.utils.crc import CRC -from unitree_sdk2py.utils.thread import Thread -import unitree_go2_const as go2 - -crc = CRC() -lowCmdThreadPtr=Thread() - -if __name__ == '__main__': - - ChannelFactoryInitialize(1, "enp2s0") - # Create a publisher to publish the data defined in UserData class - pub = ChannelPublisher("lowcmd", LowCmd_) - pub.Init() - - while True: - # Create a Userdata message - cmd = unitree_go_msg_dds__LowCmd_() - - # Toque controle, set RL_2 toque - cmd.motor_cmd[go2.LegID["RL_2"]].mode = 0x01 - cmd.motor_cmd[go2.LegID["RL_2"]].q = go2.PosStopF # Set to stop position(rad) - cmd.motor_cmd[go2.LegID["RL_2"]].kp = 0 - cmd.motor_cmd[go2.LegID["RL_2"]].dq = go2.VelStopF # Set to stop angular velocity(rad/s) - cmd.motor_cmd[go2.LegID["RL_2"]].kd = 0 - cmd.motor_cmd[go2.LegID["RL_2"]].tau = 1 # target toque is set to 1N.m - - # Poinstion(rad) control, set RL_0 rad - cmd.motor_cmd[go2.LegID["RL_0"]].mode = 0x01 - cmd.motor_cmd[go2.LegID["RL_0"]].q = 0 # Taregt angular(rad) - cmd.motor_cmd[go2.LegID["RL_0"]].kp = 10 # Poinstion(rad) control kp gain - cmd.motor_cmd[go2.LegID["RL_0"]].dq = 0 # Taregt angular velocity(rad/ss) - cmd.motor_cmd[go2.LegID["RL_0"]].kd = 1 # Poinstion(rad) control kd gain - cmd.motor_cmd[go2.LegID["RL_0"]].tau = 0 # Feedforward toque 1N.m - - cmd.crc = crc.Crc(cmd) - - #Publish message - if pub.Write(cmd): - print("Publish success. msg:", cmd.crc) - else: - print("Waitting for subscriber.") - - time.sleep(0.002) - - pub.Close() +import time + +from unitree_sdk2py.core.channel import ChannelPublisher, ChannelFactoryInitialize +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowCmd_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowCmd_ +from unitree_sdk2py.utils.crc import CRC +from unitree_sdk2py.utils.thread import Thread +import unitree_go2_const as go2 + +crc = CRC() +lowCmdThreadPtr=Thread() + +if __name__ == '__main__': + + ChannelFactoryInitialize(1, "enp2s0") + # Create a publisher to publish the data defined in UserData class + pub = ChannelPublisher("lowcmd", LowCmd_) + pub.Init() + + while True: + # Create a Userdata message + cmd = unitree_go_msg_dds__LowCmd_() + + # Toque controle, set RL_2 toque + cmd.motor_cmd[go2.LegID["RL_2"]].mode = 0x01 + cmd.motor_cmd[go2.LegID["RL_2"]].q = go2.PosStopF # Set to stop position(rad) + cmd.motor_cmd[go2.LegID["RL_2"]].kp = 0 + cmd.motor_cmd[go2.LegID["RL_2"]].dq = go2.VelStopF # Set to stop angular velocity(rad/s) + cmd.motor_cmd[go2.LegID["RL_2"]].kd = 0 + cmd.motor_cmd[go2.LegID["RL_2"]].tau = 1 # target toque is set to 1N.m + + # Poinstion(rad) control, set RL_0 rad + cmd.motor_cmd[go2.LegID["RL_0"]].mode = 0x01 + cmd.motor_cmd[go2.LegID["RL_0"]].q = 0 # Taregt angular(rad) + cmd.motor_cmd[go2.LegID["RL_0"]].kp = 10 # Poinstion(rad) control kp gain + cmd.motor_cmd[go2.LegID["RL_0"]].dq = 0 # Taregt angular velocity(rad/ss) + cmd.motor_cmd[go2.LegID["RL_0"]].kd = 1 # Poinstion(rad) control kd gain + cmd.motor_cmd[go2.LegID["RL_0"]].tau = 0 # Feedforward toque 1N.m + + cmd.crc = crc.Crc(cmd) + + #Publish message + if pub.Write(cmd): + print("Publish success. msg:", cmd.crc) + else: + print("Waitting for subscriber.") + + time.sleep(0.002) + + pub.Close() diff --git a/unitree_sdk2py/test/lowlevel/read_lowstate.py b/unitree_sdk2py/test/lowlevel/read_lowstate.py index d3f20ca..8a03332 100644 --- a/unitree_sdk2py/test/lowlevel/read_lowstate.py +++ b/unitree_sdk2py/test/lowlevel/read_lowstate.py @@ -1,24 +1,24 @@ -import time -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowState_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowState_ - -import unitree_go2_const as go2 - - -def LowStateHandler(msg: LowState_): - - # print front right hip motor states - print("FR_0 motor state: ", msg.motor_state[go2.LegID["FR_0"]]) - print("IMU state: ", msg.imu_state) - print("Battery state: voltage: ", msg.power_v, "current: ", msg.power_a) - - -if __name__ == "__main__": - # Modify "enp2s0" to the actual network interface - ChannelFactoryInitialize(0, "enp2s0") - sub = ChannelSubscriber("rt/lowstate", LowState_) - sub.Init(LowStateHandler, 10) - - while True: - time.sleep(10.0) +import time +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowState_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowState_ + +import unitree_go2_const as go2 + + +def LowStateHandler(msg: LowState_): + + # print front right hip motor states + print("FR_0 motor state: ", msg.motor_state[go2.LegID["FR_0"]]) + print("IMU state: ", msg.imu_state) + print("Battery state: voltage: ", msg.power_v, "current: ", msg.power_a) + + +if __name__ == "__main__": + # Modify "enp2s0" to the actual network interface + ChannelFactoryInitialize(0, "enp2s0") + sub = ChannelSubscriber("rt/lowstate", LowState_) + sub.Init(LowStateHandler, 10) + + while True: + time.sleep(10.0) diff --git a/unitree_sdk2py/test/lowlevel/sub_lowstate.py b/unitree_sdk2py/test/lowlevel/sub_lowstate.py index 9a94619..707a517 100644 --- a/unitree_sdk2py/test/lowlevel/sub_lowstate.py +++ b/unitree_sdk2py/test/lowlevel/sub_lowstate.py @@ -1,15 +1,15 @@ -import time -from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize -from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowState_ -from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowState_ - -def LowStateHandler(msg: LowState_): - print(msg.motor_state) - - -ChannelFactoryInitialize(0, "enp2s0") -sub = ChannelSubscriber("rt/lowstate", LowState_) -sub.Init(LowStateHandler, 10) - -while True: +import time +from unitree_sdk2py.core.channel import ChannelSubscriber, ChannelFactoryInitialize +from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowState_ +from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowState_ + +def LowStateHandler(msg: LowState_): + print(msg.motor_state) + + +ChannelFactoryInitialize(0, "enp2s0") +sub = ChannelSubscriber("rt/lowstate", LowState_) +sub.Init(LowStateHandler, 10) + +while True: time.sleep(10.0) \ No newline at end of file diff --git a/unitree_sdk2py/test/lowlevel/unitree_go2_const.py b/unitree_sdk2py/test/lowlevel/unitree_go2_const.py index 153a051..dc130ca 100644 --- a/unitree_sdk2py/test/lowlevel/unitree_go2_const.py +++ b/unitree_sdk2py/test/lowlevel/unitree_go2_const.py @@ -1,20 +1,20 @@ -LegID = { - "FR_0": 0, # Front right hip - "FR_1": 1, # Front right thigh - "FR_2": 2, # Front right calf - "FL_0": 3, - "FL_1": 4, - "FL_2": 5, - "RR_0": 6, - "RR_1": 7, - "RR_2": 8, - "RL_0": 9, - "RL_1": 10, - "RL_2": 11, -} - -HIGHLEVEL = 0xEE -LOWLEVEL = 0xFF -TRIGERLEVEL = 0xF0 -PosStopF = 2.146e9 -VelStopF = 16000.0 +LegID = { + "FR_0": 0, # Front right hip + "FR_1": 1, # Front right thigh + "FR_2": 2, # Front right calf + "FL_0": 3, + "FL_1": 4, + "FL_2": 5, + "RR_0": 6, + "RR_1": 7, + "RR_2": 8, + "RL_0": 9, + "RL_1": 10, + "RL_2": 11, +} + +HIGHLEVEL = 0xEE +LOWLEVEL = 0xFF +TRIGERLEVEL = 0xF0 +PosStopF = 2.146e9 +VelStopF = 16000.0 diff --git a/unitree_sdk2py/test/rpc/test_api.py b/unitree_sdk2py/test/rpc/test_api.py index 68778ca..c1092a8 100644 --- a/unitree_sdk2py/test/rpc/test_api.py +++ b/unitree_sdk2py/test/rpc/test_api.py @@ -1,9 +1,9 @@ -# service name -TEST_SERVICE_NAME = "test" - -# api version -TEST_API_VERSION = "1.0.0.1" - -# api id -TEST_API_ID_MOVE = 1008 +# service name +TEST_SERVICE_NAME = "test" + +# api version +TEST_API_VERSION = "1.0.0.1" + +# api id +TEST_API_ID_MOVE = 1008 TEST_API_ID_STOP = 1002 \ No newline at end of file diff --git a/unitree_sdk2py/test/rpc/test_client_example.py b/unitree_sdk2py/test/rpc/test_client_example.py index 35c6ad4..0c7e9f2 100644 --- a/unitree_sdk2py/test/rpc/test_client_example.py +++ b/unitree_sdk2py/test/rpc/test_client_example.py @@ -1,62 +1,62 @@ -import time -import json - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.rpc.client import Client - -from test_api import * - -""" -" class TestClient -""" -class TestClient(Client): - def __init__(self, enableLease: bool = False): - super().__init__("test", enableLease) - - def Init(self): - self._RegistApi(TEST_API_ID_MOVE, 0) - self._RegistApi(TEST_API_ID_STOP, 1) - self._SetApiVerson(TEST_API_VERSION) - - def Move(self, vx: float, vy: float, vyaw: float): - parameter = {} - parameter["vx"] = vx - parameter["vy"] = vy - parameter["vyaw"] = vyaw - p = json.dumps(parameter) - - c, d = self._Call(TEST_API_ID_MOVE, p) - return c - - def Stop(self): - parameter = {} - p = json.dumps(parameter) - - c, d = self._Call(TEST_API_ID_STOP, p) - return c - -if __name__ == "__main__": - # initialize channel factory. - ChannelFactoryInitialize(0) - - # create client - client = TestClient(True) - client.Init() - client.SetTimeout(5.0) - - # get server version - code, serverApiVersion = client.GetServerApiVersion() - print("server api version:", serverApiVersion) - - # wait lease applied - client.WaitLeaseApplied() - - # test api - while True: - code = client.Move(0.2, 0, 0) - print("client move ret:", code) - time.sleep(1.0) - - code = client.Stop() - print("client stop ret:", code) - time.sleep(1.0) +import time +import json + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.rpc.client import Client + +from test_api import * + +""" +" class TestClient +""" +class TestClient(Client): + def __init__(self, enableLease: bool = False): + super().__init__("test", enableLease) + + def Init(self): + self._RegistApi(TEST_API_ID_MOVE, 0) + self._RegistApi(TEST_API_ID_STOP, 1) + self._SetApiVerson(TEST_API_VERSION) + + def Move(self, vx: float, vy: float, vyaw: float): + parameter = {} + parameter["vx"] = vx + parameter["vy"] = vy + parameter["vyaw"] = vyaw + p = json.dumps(parameter) + + c, d = self._Call(TEST_API_ID_MOVE, p) + return c + + def Stop(self): + parameter = {} + p = json.dumps(parameter) + + c, d = self._Call(TEST_API_ID_STOP, p) + return c + +if __name__ == "__main__": + # initialize channel factory. + ChannelFactoryInitialize(0) + + # create client + client = TestClient(True) + client.Init() + client.SetTimeout(5.0) + + # get server version + code, serverApiVersion = client.GetServerApiVersion() + print("server api version:", serverApiVersion) + + # wait lease applied + client.WaitLeaseApplied() + + # test api + while True: + code = client.Move(0.2, 0, 0) + print("client move ret:", code) + time.sleep(1.0) + + code = client.Stop() + print("client stop ret:", code) + time.sleep(1.0) diff --git a/unitree_sdk2py/test/rpc/test_server_example.py b/unitree_sdk2py/test/rpc/test_server_example.py index a929e01..f5268d7 100644 --- a/unitree_sdk2py/test/rpc/test_server_example.py +++ b/unitree_sdk2py/test/rpc/test_server_example.py @@ -1,45 +1,45 @@ -import time -import json - -from unitree_sdk2py.core.channel import ChannelFactoryInitialize -from unitree_sdk2py.rpc.server import Server - -from test_api import * - - -""" -" class TestServer -""" -class TestServer(Server): - def __init__(self): - super().__init__("test") - - def Init(self): - self._RegistHandler(TEST_API_ID_MOVE, self.Move, 1) - self._RegistHandler(TEST_API_ID_STOP, self.Stop, 0) - self._SetApiVersion(TEST_API_VERSION) - - def Move(self, parameter: str): - p = json.loads(parameter) - x = p["vx"] - y = p["vy"] - yaw = p["vyaw"] - print("Move Called. vx:", x, ", vy:", y, ", vyaw:", yaw) - return 0, "" - - def Stop(self, parameter: str): - print("Stop Called.") - return 0, "" - -if __name__ == "__main__": - # initialize channel factory. - ChannelFactoryInitialize(0) - - # create server - server = TestServer() - server.Init() - server.StartLease(1.0) - server.Start(False) - - while True: +import time +import json + +from unitree_sdk2py.core.channel import ChannelFactoryInitialize +from unitree_sdk2py.rpc.server import Server + +from test_api import * + + +""" +" class TestServer +""" +class TestServer(Server): + def __init__(self): + super().__init__("test") + + def Init(self): + self._RegistHandler(TEST_API_ID_MOVE, self.Move, 1) + self._RegistHandler(TEST_API_ID_STOP, self.Stop, 0) + self._SetApiVersion(TEST_API_VERSION) + + def Move(self, parameter: str): + p = json.loads(parameter) + x = p["vx"] + y = p["vy"] + yaw = p["vyaw"] + print("Move Called. vx:", x, ", vy:", y, ", vyaw:", yaw) + return 0, "" + + def Stop(self, parameter: str): + print("Stop Called.") + return 0, "" + +if __name__ == "__main__": + # initialize channel factory. + ChannelFactoryInitialize(0) + + # create server + server = TestServer() + server.Init() + server.StartLease(1.0) + server.Start(False) + + while True: time.sleep(10) \ No newline at end of file diff --git a/unitree_sdk2py/utils/bqueue.py b/unitree_sdk2py/utils/bqueue.py index a612bfb..6e3dd8a 100644 --- a/unitree_sdk2py/utils/bqueue.py +++ b/unitree_sdk2py/utils/bqueue.py @@ -1,58 +1,58 @@ -from typing import Any -from collections import deque -from threading import Condition - -class BQueue: - def __init__(self, maxLen: int = 10): - self.__curLen = 0 - self.__maxLen = maxLen - self.__queue = deque() - self.__condition = Condition() - - def Put(self, x: Any, replace: bool = False): - noReplaced = True - with self.__condition: - if self.__curLen >= self.__maxLen: - if not replace: - return False - else: - noReplaced = False - self.__queue.popleft() - self.__curLen -= 1 - - self.__queue.append(x) - self.__curLen += 1 - self.__condition.notify() - - return noReplaced - - def Get(self, timeout: float = None): - with self.__condition: - if not self.__queue: - try: - self.__condition.wait(timeout) - except: - return None - - if not self.__queue: - return None - - self.__curLen -= 1 - return self.__queue.popleft() - - def Clear(self): - with self.__condition: - if self.__queue: - self.__queue.clear() - self.__curLen = 0 - - def Size(self): - with self.__condition: - return self.__curLen - - def Interrupt(self, notifyAll: bool = False): - with self.__condition: - if notifyAll: - self.__condition.notify() - else: - self.__condition.notify_all() +from typing import Any +from collections import deque +from threading import Condition + +class BQueue: + def __init__(self, maxLen: int = 10): + self.__curLen = 0 + self.__maxLen = maxLen + self.__queue = deque() + self.__condition = Condition() + + def Put(self, x: Any, replace: bool = False): + noReplaced = True + with self.__condition: + if self.__curLen >= self.__maxLen: + if not replace: + return False + else: + noReplaced = False + self.__queue.popleft() + self.__curLen -= 1 + + self.__queue.append(x) + self.__curLen += 1 + self.__condition.notify() + + return noReplaced + + def Get(self, timeout: float = None): + with self.__condition: + if not self.__queue: + try: + self.__condition.wait(timeout) + except: + return None + + if not self.__queue: + return None + + self.__curLen -= 1 + return self.__queue.popleft() + + def Clear(self): + with self.__condition: + if self.__queue: + self.__queue.clear() + self.__curLen = 0 + + def Size(self): + with self.__condition: + return self.__curLen + + def Interrupt(self, notifyAll: bool = False): + with self.__condition: + if notifyAll: + self.__condition.notify() + else: + self.__condition.notify_all() diff --git a/unitree_sdk2py/utils/clib_lookup.py b/unitree_sdk2py/utils/clib_lookup.py index ca7073d..fc93018 100644 --- a/unitree_sdk2py/utils/clib_lookup.py +++ b/unitree_sdk2py/utils/clib_lookup.py @@ -1,17 +1,17 @@ -import os -import ctypes - -clib = ctypes.CDLL(None, use_errno=True) - -def CLIBCheckError(ret, func, args): - if ret < 0: - code = ctypes.get_errno() - raise OSError(code, os.strerror(code)) - return ret - -def CLIBLookup(name, resType, argTypes): - func = clib[name] - func.restye = resType - func.argtypes = argTypes - func.errcheck = CLIBCheckError - return func +import os +import ctypes + +clib = ctypes.CDLL(None, use_errno=True) + +def CLIBCheckError(ret, func, args): + if ret < 0: + code = ctypes.get_errno() + raise OSError(code, os.strerror(code)) + return ret + +def CLIBLookup(name, resType, argTypes): + func = clib[name] + func.restye = resType + func.argtypes = argTypes + func.errcheck = CLIBCheckError + return func diff --git a/unitree_sdk2py/utils/crc.py b/unitree_sdk2py/utils/crc.py index d7dc44f..f36de36 100644 --- a/unitree_sdk2py/utils/crc.py +++ b/unitree_sdk2py/utils/crc.py @@ -1,140 +1,140 @@ -import struct -import cyclonedds -import cyclonedds.idl as idl - -from .singleton import Singleton -from ..idl.unitree_go.msg.dds_ import LowCmd_ as LowCmd -from ..idl.unitree_go.msg.dds_ import LowState_ as LowState - -class CRC(Singleton): - def __init__(self): - #4 bytes aligned, little-endian format. - #size 812 - self.__packFmtLowCmd = '<4B4IH2x' + 'B3x5f3I' * 20 + '4B' + '55Bx2I' - #size 1180 - self.__packFmtLowState = '<4B4IH2x' + '13fb3x' + 'B3x7fb3x3I' * 20 + '4BiH4b15H' + '8hI41B3xf2b2x2f4h2I' - - def Crc(self, msg: idl.IdlStruct): - if msg.__idl_typename__ == 'unitree_go.msg.dds_.LowCmd_': - return self.__Crc32(self.__PackLowCmd(msg)) - elif msg.__idl_typename__ == 'unitree_go.msg.dds_.LowState_': - return self.__Crc32(self.__PackLowState(msg)) - else: - raise TypeError('unknown IDL message type to crc') - - def __PackLowCmd(self, cmd: LowCmd): - origData = [] - origData.extend(cmd.head) - origData.append(cmd.level_flag) - origData.append(cmd.frame_reserve) - origData.extend(cmd.sn) - origData.extend(cmd.version) - origData.append(cmd.bandwidth) - - for i in range(20): - origData.append(cmd.motor_cmd[i].mode) - origData.append(cmd.motor_cmd[i].q) - origData.append(cmd.motor_cmd[i].dq) - origData.append(cmd.motor_cmd[i].tau) - origData.append(cmd.motor_cmd[i].kp) - origData.append(cmd.motor_cmd[i].kd) - origData.extend(cmd.motor_cmd[i].reserve) - - origData.append(cmd.bms_cmd.off) - origData.extend(cmd.bms_cmd.reserve) - - origData.extend(cmd.wireless_remote) - origData.extend(cmd.led) - origData.extend(cmd.fan) - origData.append(cmd.gpio) - origData.append(cmd.reserve) - origData.append(cmd.crc) - - return self.__Trans(struct.pack(self.__packFmtLowCmd, *origData)) - - def __PackLowState(self, state: LowState): - origData = [] - origData.extend(state.head) - origData.append(state.level_flag) - origData.append(state.frame_reserve) - origData.extend(state.sn) - origData.extend(state.version) - origData.append(state.bandwidth) - - origData.extend(state.imu_state.quaternion) - origData.extend(state.imu_state.gyroscope) - origData.extend(state.imu_state.accelerometer) - origData.extend(state.imu_state.rpy) - origData.append(state.imu_state.temperature) - - for i in range(20): - origData.append(state.motor_state[i].mode) - origData.append(state.motor_state[i].q) - origData.append(state.motor_state[i].dq) - origData.append(state.motor_state[i].ddq) - origData.append(state.motor_state[i].tau_est) - origData.append(state.motor_state[i].q_raw) - origData.append(state.motor_state[i].dq_raw) - origData.append(state.motor_state[i].ddq_raw) - origData.append(state.motor_state[i].temperature) - origData.append(state.motor_state[i].lost) - origData.extend(state.motor_state[i].reserve) - - origData.append(state.bms_state.version_high) - origData.append(state.bms_state.version_low) - origData.append(state.bms_state.status) - origData.append(state.bms_state.soc) - origData.append(state.bms_state.current) - origData.append(state.bms_state.cycle) - origData.extend(state.bms_state.bq_ntc) - origData.extend(state.bms_state.mcu_ntc) - origData.extend(state.bms_state.cell_vol) - - origData.extend(state.foot_force) - origData.extend(state.foot_force_est) - origData.append(state.tick) - origData.extend(state.wireless_remote) - origData.append(state.bit_flag) - origData.append(state.adc_reel) - origData.append(state.temperature_ntc1) - origData.append(state.temperature_ntc2) - origData.append(state.power_v) - origData.append(state.power_a) - origData.extend(state.fan_frequency) - origData.append(state.reserve) - origData.append(state.crc) - - return self.__Trans(struct.pack(self.__packFmtLowState, *origData)) - - def __Trans(self, packData): - calcData = [] - calcLen = ((len(packData)>>2)-1) - - for i in range(calcLen): - d = ((packData[i*4+3] << 24) | (packData[i*4+2] << 16) | (packData[i*4+1] << 8) | (packData[i*4])) - calcData.append(d) - - return calcData - - def __Crc32(self, data): - bit = 0 - crc = 0xFFFFFFFF - polynomial = 0x04c11db7 - - for i in range(len(data)): - bit = 1 << 31 - current = data[i] - - for b in range(32): - if crc & 0x80000000: - crc = (crc << 1) & 0xFFFFFFFF - crc ^= polynomial - else: - crc = (crc << 1) & 0xFFFFFFFF - - if current & bit: - crc ^= polynomial - - bit >>= 1 - - return crc +import struct +import cyclonedds +import cyclonedds.idl as idl + +from .singleton import Singleton +from ..idl.unitree_go.msg.dds_ import LowCmd_ as LowCmd +from ..idl.unitree_go.msg.dds_ import LowState_ as LowState + +class CRC(Singleton): + def __init__(self): + #4 bytes aligned, little-endian format. + #size 812 + self.__packFmtLowCmd = '<4B4IH2x' + 'B3x5f3I' * 20 + '4B' + '55Bx2I' + #size 1180 + self.__packFmtLowState = '<4B4IH2x' + '13fb3x' + 'B3x7fb3x3I' * 20 + '4BiH4b15H' + '8hI41B3xf2b2x2f4h2I' + + def Crc(self, msg: idl.IdlStruct): + if msg.__idl_typename__ == 'unitree_go.msg.dds_.LowCmd_': + return self.__Crc32(self.__PackLowCmd(msg)) + elif msg.__idl_typename__ == 'unitree_go.msg.dds_.LowState_': + return self.__Crc32(self.__PackLowState(msg)) + else: + raise TypeError('unknown IDL message type to crc') + + def __PackLowCmd(self, cmd: LowCmd): + origData = [] + origData.extend(cmd.head) + origData.append(cmd.level_flag) + origData.append(cmd.frame_reserve) + origData.extend(cmd.sn) + origData.extend(cmd.version) + origData.append(cmd.bandwidth) + + for i in range(20): + origData.append(cmd.motor_cmd[i].mode) + origData.append(cmd.motor_cmd[i].q) + origData.append(cmd.motor_cmd[i].dq) + origData.append(cmd.motor_cmd[i].tau) + origData.append(cmd.motor_cmd[i].kp) + origData.append(cmd.motor_cmd[i].kd) + origData.extend(cmd.motor_cmd[i].reserve) + + origData.append(cmd.bms_cmd.off) + origData.extend(cmd.bms_cmd.reserve) + + origData.extend(cmd.wireless_remote) + origData.extend(cmd.led) + origData.extend(cmd.fan) + origData.append(cmd.gpio) + origData.append(cmd.reserve) + origData.append(cmd.crc) + + return self.__Trans(struct.pack(self.__packFmtLowCmd, *origData)) + + def __PackLowState(self, state: LowState): + origData = [] + origData.extend(state.head) + origData.append(state.level_flag) + origData.append(state.frame_reserve) + origData.extend(state.sn) + origData.extend(state.version) + origData.append(state.bandwidth) + + origData.extend(state.imu_state.quaternion) + origData.extend(state.imu_state.gyroscope) + origData.extend(state.imu_state.accelerometer) + origData.extend(state.imu_state.rpy) + origData.append(state.imu_state.temperature) + + for i in range(20): + origData.append(state.motor_state[i].mode) + origData.append(state.motor_state[i].q) + origData.append(state.motor_state[i].dq) + origData.append(state.motor_state[i].ddq) + origData.append(state.motor_state[i].tau_est) + origData.append(state.motor_state[i].q_raw) + origData.append(state.motor_state[i].dq_raw) + origData.append(state.motor_state[i].ddq_raw) + origData.append(state.motor_state[i].temperature) + origData.append(state.motor_state[i].lost) + origData.extend(state.motor_state[i].reserve) + + origData.append(state.bms_state.version_high) + origData.append(state.bms_state.version_low) + origData.append(state.bms_state.status) + origData.append(state.bms_state.soc) + origData.append(state.bms_state.current) + origData.append(state.bms_state.cycle) + origData.extend(state.bms_state.bq_ntc) + origData.extend(state.bms_state.mcu_ntc) + origData.extend(state.bms_state.cell_vol) + + origData.extend(state.foot_force) + origData.extend(state.foot_force_est) + origData.append(state.tick) + origData.extend(state.wireless_remote) + origData.append(state.bit_flag) + origData.append(state.adc_reel) + origData.append(state.temperature_ntc1) + origData.append(state.temperature_ntc2) + origData.append(state.power_v) + origData.append(state.power_a) + origData.extend(state.fan_frequency) + origData.append(state.reserve) + origData.append(state.crc) + + return self.__Trans(struct.pack(self.__packFmtLowState, *origData)) + + def __Trans(self, packData): + calcData = [] + calcLen = ((len(packData)>>2)-1) + + for i in range(calcLen): + d = ((packData[i*4+3] << 24) | (packData[i*4+2] << 16) | (packData[i*4+1] << 8) | (packData[i*4])) + calcData.append(d) + + return calcData + + def __Crc32(self, data): + bit = 0 + crc = 0xFFFFFFFF + polynomial = 0x04c11db7 + + for i in range(len(data)): + bit = 1 << 31 + current = data[i] + + for b in range(32): + if crc & 0x80000000: + crc = (crc << 1) & 0xFFFFFFFF + crc ^= polynomial + else: + crc = (crc << 1) & 0xFFFFFFFF + + if current & bit: + crc ^= polynomial + + bit >>= 1 + + return crc diff --git a/unitree_sdk2py/utils/future.py b/unitree_sdk2py/utils/future.py index f539087..d36c80e 100644 --- a/unitree_sdk2py/utils/future.py +++ b/unitree_sdk2py/utils/future.py @@ -1,104 +1,104 @@ -from threading import Condition -from typing import Any -from enum import Enum - -""" -" Enum RequtestFutureState -""" -class FutureState(Enum): - DEFER = 0 - READY = 1 - FAILED = 2 - -""" -" class FutureException -""" -class FutureResult: - FUTURE_SUCC = 0 - FUTUTE_ERR_TIMEOUT = 1 - FUTURE_ERR_FAILED = 2 - FUTURE_ERR_UNKNOWN = 3 - - def __init__(self, code: int, msg: str, value: Any = None): - self.code = code - self.msg = msg - self.value = value - - def __str__(self): - return f"FutureResult(code={str(self.code)}, msg='{self.msg}', value={self.value})" - -class Future: - def __init__(self): - self.__state = FutureState.DEFER - self.__msg = None - self.__condition = Condition() - - def GetResult(self, timeout: float = None): - with self.__condition: - return self.__WaitResult(timeout) - - def Wait(self, timeout: float = None): - with self.__condition: - return self.__Wait(timeout) - - def Ready(self, value): - with self.__condition: - ready = self.__Ready(value) - self.__condition.notify() - return ready - - def Fail(self, reason: str): - with self.__condition: - fail = self.__Fail(reason) - self.__condition.notify() - return fail - - def __Wait(self, timeout: float = None): - if not self.__IsDeferred(): - return True - try: - if timeout is None: - return self.__condition.wait() - else: - return self.__condition.wait(timeout) - except: - print("[Future] future wait error") - return False - - def __WaitResult(self, timeout: float = None): - if not self.__Wait(timeout): - return FutureResult(FutureResult.FUTUTE_ERR_TIMEOUT, "future wait timeout") - - if self.__IsReady(): - return FutureResult(FutureResult.FUTURE_SUCC, "success", self.__value) - elif self.__IsFailed(): - return FutureResult(FutureResult.FUTURE_ERR_FAILED, self.__msg) - else: - return FutureResult(FutureResult.FUTURE_ERR_UNKNOWN, "future state error:" + str(self.__state)) - - def __Ready(self, value): - if not self.__IsDeferred(): - print("[Future] futrue state is not defer") - return False - else: - self.__value = value - self.__state = FutureState.READY - return True - - def __Fail(self, message: str): - if not self.__IsDeferred(): - print("[Future] futrue state is not DEFER") - return False - else: - self.__msg = message - self.__state = FutureState.FAILED - return True - - def __IsDeferred(self): - return self.__state == FutureState.DEFER - - def __IsReady(self): - return self.__state == FutureState.READY - - def __IsFailed(self): +from threading import Condition +from typing import Any +from enum import Enum + +""" +" Enum RequtestFutureState +""" +class FutureState(Enum): + DEFER = 0 + READY = 1 + FAILED = 2 + +""" +" class FutureException +""" +class FutureResult: + FUTURE_SUCC = 0 + FUTUTE_ERR_TIMEOUT = 1 + FUTURE_ERR_FAILED = 2 + FUTURE_ERR_UNKNOWN = 3 + + def __init__(self, code: int, msg: str, value: Any = None): + self.code = code + self.msg = msg + self.value = value + + def __str__(self): + return f"FutureResult(code={str(self.code)}, msg='{self.msg}', value={self.value})" + +class Future: + def __init__(self): + self.__state = FutureState.DEFER + self.__msg = None + self.__condition = Condition() + + def GetResult(self, timeout: float = None): + with self.__condition: + return self.__WaitResult(timeout) + + def Wait(self, timeout: float = None): + with self.__condition: + return self.__Wait(timeout) + + def Ready(self, value): + with self.__condition: + ready = self.__Ready(value) + self.__condition.notify() + return ready + + def Fail(self, reason: str): + with self.__condition: + fail = self.__Fail(reason) + self.__condition.notify() + return fail + + def __Wait(self, timeout: float = None): + if not self.__IsDeferred(): + return True + try: + if timeout is None: + return self.__condition.wait() + else: + return self.__condition.wait(timeout) + except: + print("[Future] future wait error") + return False + + def __WaitResult(self, timeout: float = None): + if not self.__Wait(timeout): + return FutureResult(FutureResult.FUTUTE_ERR_TIMEOUT, "future wait timeout") + + if self.__IsReady(): + return FutureResult(FutureResult.FUTURE_SUCC, "success", self.__value) + elif self.__IsFailed(): + return FutureResult(FutureResult.FUTURE_ERR_FAILED, self.__msg) + else: + return FutureResult(FutureResult.FUTURE_ERR_UNKNOWN, "future state error:" + str(self.__state)) + + def __Ready(self, value): + if not self.__IsDeferred(): + print("[Future] futrue state is not defer") + return False + else: + self.__value = value + self.__state = FutureState.READY + return True + + def __Fail(self, message: str): + if not self.__IsDeferred(): + print("[Future] futrue state is not DEFER") + return False + else: + self.__msg = message + self.__state = FutureState.FAILED + return True + + def __IsDeferred(self): + return self.__state == FutureState.DEFER + + def __IsReady(self): + return self.__state == FutureState.READY + + def __IsFailed(self): return self.__state == FutureState.FAILED \ No newline at end of file diff --git a/unitree_sdk2py/utils/hz_sample.py b/unitree_sdk2py/utils/hz_sample.py index 962fe3c..1c3fd0a 100644 --- a/unitree_sdk2py/utils/hz_sample.py +++ b/unitree_sdk2py/utils/hz_sample.py @@ -1,24 +1,24 @@ -import time -from threading import Lock -from .thread import RecurrentThread - -class HZSample: - def __init__(self, interval: float = 1.0): - self.__count = 0 - self.__inter = interval if interval > 0.0 else 1.0 - self.__lock = Lock() - self.__thread = RecurrentThread(self.__inter, target=self.TimerFunc) - - def Start(self): - self.__thread.Start() - - def Sample(self): - with self.__lock: - self.__count += 1 - - def TimerFunc(self): - count = 0 - with self.__lock: - count = self.__count - self.__count = 0 - print("HZ: {}".format(count/self.__inter)) +import time +from threading import Lock +from .thread import RecurrentThread + +class HZSample: + def __init__(self, interval: float = 1.0): + self.__count = 0 + self.__inter = interval if interval > 0.0 else 1.0 + self.__lock = Lock() + self.__thread = RecurrentThread(self.__inter, target=self.TimerFunc) + + def Start(self): + self.__thread.Start() + + def Sample(self): + with self.__lock: + self.__count += 1 + + def TimerFunc(self): + count = 0 + with self.__lock: + count = self.__count + self.__count = 0 + print("HZ: {}".format(count/self.__inter)) diff --git a/unitree_sdk2py/utils/singleton.py b/unitree_sdk2py/utils/singleton.py index 62ca3b0..1074457 100644 --- a/unitree_sdk2py/utils/singleton.py +++ b/unitree_sdk2py/utils/singleton.py @@ -1,11 +1,11 @@ -class Singleton: - __instance = None - - def __new__(cls, *args, **kwargs): - if cls.__instance is None: - cls.__instance = super(Singleton, cls).__new__(cls) - return cls.__instance - - def __init__(self): - pass - +class Singleton: + __instance = None + + def __new__(cls, *args, **kwargs): + if cls.__instance is None: + cls.__instance = super(Singleton, cls).__new__(cls) + return cls.__instance + + def __init__(self): + pass + diff --git a/unitree_sdk2py/utils/thread.py b/unitree_sdk2py/utils/thread.py index f17cf4e..a8e6fea 100644 --- a/unitree_sdk2py/utils/thread.py +++ b/unitree_sdk2py/utils/thread.py @@ -1,83 +1,83 @@ -import sys -import os -import errno -import ctypes -import struct -import threading - -from .future import Future -from .timerfd import * - -class Thread(Future): - def __init__(self, target = None, name = None, args = (), kwargs = None): - super().__init__() - self.__target = target - self.__args = args - self.__kwargs = {} if kwargs is None else kwargs - self.__thread = threading.Thread(target=self.__ThreadFunc, name=name, daemon=True) - - def Start(self): - return self.__thread.start() - - def GetId(self): - return self.__thread.ident - - def GetNativeId(self): - return self.__thread.native_id - - def __ThreadFunc(self): - value = None - try: - value = self.__target(*self.__args, **self.__kwargs) - self.Ready(value) - except: - info = sys.exc_info() - self.Fail(f"[Thread] target func raise exception: name={info[0].__name__}, args={str(info[1].args)}") - -class RecurrentThread(Thread): - def __init__(self, interval: float = 1.0, target = None, name = None, args = (), kwargs = None): - self.__quit = False - self.__inter = interval - self.__loopTarget = target - self.__loopArgs = args - self.__loopKwargs = {} if kwargs is None else kwargs - - if interval is None or interval <= 0.0: - super().__init__(target=self.__LoopFunc_0, name=name) - else: - super().__init__(target=self.__LoopFunc, name=name) - - def Wait(self, timeout: float = None): - self.__quit = True - super().Wait(timeout) - - def __LoopFunc(self): - # clock type CLOCK_MONOTONIC = 1 - tfd = timerfd_create(1, 0) - spec = itimerspec.from_seconds(self.__inter, self.__inter) - timerfd_settime(tfd, 0, ctypes.byref(spec), None) - - while not self.__quit: - try: - self.__loopTarget(*self.__loopArgs, **self.__loopKwargs) - except: - info = sys.exc_info() - print(f"[RecurrentThread] target func raise exception: name={info[0].__name__}, args={str(info[1].args)}") - - try: - buf = os.read(tfd, 8) - # print(struct.unpack("Q", buf)[0]) - except OSError as e: - if e.errno != errno.EAGAIN: - raise e - - os.close(tfd) - - def __LoopFunc_0(self): - while not self.__quit: - try: - self.__loopTarget(*self.__args, **self.__kwargs) - except: - info = sys.exc_info() - print(f"[RecurrentThread] target func raise exception: name={info[0].__name__}, args={str(info[1].args)}") - +import sys +import os +import errno +import ctypes +import struct +import threading + +from .future import Future +from .timerfd import * + +class Thread(Future): + def __init__(self, target = None, name = None, args = (), kwargs = None): + super().__init__() + self.__target = target + self.__args = args + self.__kwargs = {} if kwargs is None else kwargs + self.__thread = threading.Thread(target=self.__ThreadFunc, name=name, daemon=True) + + def Start(self): + return self.__thread.start() + + def GetId(self): + return self.__thread.ident + + def GetNativeId(self): + return self.__thread.native_id + + def __ThreadFunc(self): + value = None + try: + value = self.__target(*self.__args, **self.__kwargs) + self.Ready(value) + except: + info = sys.exc_info() + self.Fail(f"[Thread] target func raise exception: name={info[0].__name__}, args={str(info[1].args)}") + +class RecurrentThread(Thread): + def __init__(self, interval: float = 1.0, target = None, name = None, args = (), kwargs = None): + self.__quit = False + self.__inter = interval + self.__loopTarget = target + self.__loopArgs = args + self.__loopKwargs = {} if kwargs is None else kwargs + + if interval is None or interval <= 0.0: + super().__init__(target=self.__LoopFunc_0, name=name) + else: + super().__init__(target=self.__LoopFunc, name=name) + + def Wait(self, timeout: float = None): + self.__quit = True + super().Wait(timeout) + + def __LoopFunc(self): + # clock type CLOCK_MONOTONIC = 1 + tfd = timerfd_create(1, 0) + spec = itimerspec.from_seconds(self.__inter, self.__inter) + timerfd_settime(tfd, 0, ctypes.byref(spec), None) + + while not self.__quit: + try: + self.__loopTarget(*self.__loopArgs, **self.__loopKwargs) + except: + info = sys.exc_info() + print(f"[RecurrentThread] target func raise exception: name={info[0].__name__}, args={str(info[1].args)}") + + try: + buf = os.read(tfd, 8) + # print(struct.unpack("Q", buf)[0]) + except OSError as e: + if e.errno != errno.EAGAIN: + raise e + + os.close(tfd) + + def __LoopFunc_0(self): + while not self.__quit: + try: + self.__loopTarget(*self.__args, **self.__kwargs) + except: + info = sys.exc_info() + print(f"[RecurrentThread] target func raise exception: name={info[0].__name__}, args={str(info[1].args)}") + diff --git a/unitree_sdk2py/utils/timerfd.py b/unitree_sdk2py/utils/timerfd.py index 002ef39..d4a5a7d 100644 --- a/unitree_sdk2py/utils/timerfd.py +++ b/unitree_sdk2py/utils/timerfd.py @@ -1,45 +1,45 @@ -import math -import ctypes -from .clib_lookup import CLIBLookup - -class timespec(ctypes.Structure): - _fields_ = [("sec", ctypes.c_long), ("nsec", ctypes.c_long)] - __slots__ = [name for name,type in _fields_] - - @classmethod - def from_seconds(cls, secs): - c = cls() - c.seconds = secs - return c - - @property - def seconds(self): - return self.sec + self.nsec / 1000000000 - - @seconds.setter - def seconds(self, secs): - x, y = math.modf(secs) - self.sec = int(y) - self.nsec = int(x * 1000000000) - - -class itimerspec(ctypes.Structure): - _fields_ = [("interval", timespec),("value", timespec)] - __slots__ = [name for name,type in _fields_] - - @classmethod - def from_seconds(cls, interval, value): - spec = cls() - spec.interval.seconds = interval - spec.value.seconds = value - return spec - - -# function timerfd_create -timerfd_create = CLIBLookup("timerfd_create", ctypes.c_int, (ctypes.c_long, ctypes.c_int)) - -# function timerfd_settime -timerfd_settime = CLIBLookup("timerfd_settime", ctypes.c_int, (ctypes.c_int, ctypes.c_int, ctypes.POINTER(itimerspec), ctypes.POINTER(itimerspec))) - -# function timerfd_gettime -timerfd_gettime = CLIBLookup("timerfd_gettime", ctypes.c_int, (ctypes.c_int, ctypes.POINTER(itimerspec))) +import math +import ctypes +from .clib_lookup import CLIBLookup + +class timespec(ctypes.Structure): + _fields_ = [("sec", ctypes.c_long), ("nsec", ctypes.c_long)] + __slots__ = [name for name,type in _fields_] + + @classmethod + def from_seconds(cls, secs): + c = cls() + c.seconds = secs + return c + + @property + def seconds(self): + return self.sec + self.nsec / 1000000000 + + @seconds.setter + def seconds(self, secs): + x, y = math.modf(secs) + self.sec = int(y) + self.nsec = int(x * 1000000000) + + +class itimerspec(ctypes.Structure): + _fields_ = [("interval", timespec),("value", timespec)] + __slots__ = [name for name,type in _fields_] + + @classmethod + def from_seconds(cls, interval, value): + spec = cls() + spec.interval.seconds = interval + spec.value.seconds = value + return spec + + +# function timerfd_create +timerfd_create = CLIBLookup("timerfd_create", ctypes.c_int, (ctypes.c_long, ctypes.c_int)) + +# function timerfd_settime +timerfd_settime = CLIBLookup("timerfd_settime", ctypes.c_int, (ctypes.c_int, ctypes.c_int, ctypes.POINTER(itimerspec), ctypes.POINTER(itimerspec))) + +# function timerfd_gettime +timerfd_gettime = CLIBLookup("timerfd_gettime", ctypes.c_int, (ctypes.c_int, ctypes.POINTER(itimerspec)))