From dea0f4f73fbfc93de67b99d669264031e3896adc Mon Sep 17 00:00:00 2001
From: robofish <1683502971@qq.com>
Date: Mon, 27 Jan 2025 04:10:04 +0800
Subject: [PATCH] =?UTF-8?q?=E7=94=B5=E6=9C=BA=E5=92=8Cimu=E9=80=9A?=
=?UTF-8?q?=E8=AE=AF=E6=AD=A3=E5=B8=B8?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
.../profiles/default/devel_collisions.txt | 2 +-
.../legged_unitree_hw/devel_manifest.txt | 21 +++
.../packages/legged_unitree_hw/package.xml | 33 ++--
.../packages/unitree_motor/devel_manifest.txt | 27 +++
.../packages/unitree_motor/package.xml | 26 +++
build.sh | 10 +-
src/fdilink_ahrs/launch/ahrs_data.launch | 2 +-
.../legged_unitree_hw/CMakeLists.txt | 20 ++-
.../legged_unitree_hw/config/a1.yaml | 10 +-
.../include/legged_unitree_hw/UnitreeHW.h | 8 +-
.../legged_unitree_hw/msg/MotorFeedback.msg | 6 +
.../msg/MotorFeedbackArray.msg | 1 +
.../legged_unitree_hw/package.xml | 33 ++--
.../legged_unitree_hw/src/UnitreeHW.cpp | 60 ++++---
src/unitree_motor/CMakeLists.txt | 47 +++++
src/unitree_motor/README.md | 3 +
src/unitree_motor/include/IOPort/IOPort.h | 41 +++++
src/unitree_motor/include/crc/crc32.h | 33 ++++
src/unitree_motor/include/crc/crc_ccitt.h | 67 ++++++++
.../include/serialPort/SerialPort.h | 98 +++++++++++
.../include/serialPort/include/errorClass.h | 52 ++++++
.../unitreeMotor/include/motor_msg_A1B1.h | 162 ++++++++++++++++++
.../include/motor_msg_GO-M8010-6.h | 90 ++++++++++
.../include/unitreeMotor/unitreeMotor.h | 74 ++++++++
src/unitree_motor/launch/unitree_motor.launch | 6 +
src/unitree_motor/msg/MotorFeedback.msg | 6 +
src/unitree_motor/msg/MotorFeedbackArray.msg | 1 +
src/unitree_motor/package.xml | 26 +++
src/unitree_motor/src/changeID.cpp | 52 ++++++
src/unitree_motor/src/example_a1_motor.cpp | 35 ++++
.../src/example_a1_motor_output.cpp | 65 +++++++
src/unitree_motor/src/example_b1_motor.cpp | 35 ++++
.../src/example_goM8010_6_motor.cpp | 35 ++++
src/unitree_motor/src/unitree_motor.cpp | 71 ++++++++
34 files changed, 1197 insertions(+), 61 deletions(-)
create mode 100644 .catkin_tools/profiles/default/packages/unitree_motor/devel_manifest.txt
create mode 100644 .catkin_tools/profiles/default/packages/unitree_motor/package.xml
create mode 100644 src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedback.msg
create mode 100644 src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedbackArray.msg
create mode 100644 src/unitree_motor/CMakeLists.txt
create mode 100644 src/unitree_motor/README.md
create mode 100755 src/unitree_motor/include/IOPort/IOPort.h
create mode 100755 src/unitree_motor/include/crc/crc32.h
create mode 100644 src/unitree_motor/include/crc/crc_ccitt.h
create mode 100755 src/unitree_motor/include/serialPort/SerialPort.h
create mode 100755 src/unitree_motor/include/serialPort/include/errorClass.h
create mode 100755 src/unitree_motor/include/unitreeMotor/include/motor_msg_A1B1.h
create mode 100755 src/unitree_motor/include/unitreeMotor/include/motor_msg_GO-M8010-6.h
create mode 100755 src/unitree_motor/include/unitreeMotor/unitreeMotor.h
create mode 100644 src/unitree_motor/launch/unitree_motor.launch
create mode 100644 src/unitree_motor/msg/MotorFeedback.msg
create mode 100644 src/unitree_motor/msg/MotorFeedbackArray.msg
create mode 100644 src/unitree_motor/package.xml
create mode 100755 src/unitree_motor/src/changeID.cpp
create mode 100644 src/unitree_motor/src/example_a1_motor.cpp
create mode 100644 src/unitree_motor/src/example_a1_motor_output.cpp
create mode 100644 src/unitree_motor/src/example_b1_motor.cpp
create mode 100644 src/unitree_motor/src/example_goM8010_6_motor.cpp
create mode 100644 src/unitree_motor/src/unitree_motor.cpp
diff --git a/.catkin_tools/profiles/default/devel_collisions.txt b/.catkin_tools/profiles/default/devel_collisions.txt
index c290d7d..c00a5bd 100644
--- a/.catkin_tools/profiles/default/devel_collisions.txt
+++ b/.catkin_tools/profiles/default/devel_collisions.txt
@@ -1 +1 @@
-/home/robofish/CM_DOG/devel/./cmake.lock 843
+/home/robofish/CM_DOG/devel/./cmake.lock 1100
diff --git a/.catkin_tools/profiles/default/packages/legged_unitree_hw/devel_manifest.txt b/.catkin_tools/profiles/default/packages/legged_unitree_hw/devel_manifest.txt
index 0e74e6e..4342753 100644
--- a/.catkin_tools/profiles/default/packages/legged_unitree_hw/devel_manifest.txt
+++ b/.catkin_tools/profiles/default/packages/legged_unitree_hw/devel_manifest.txt
@@ -1,7 +1,28 @@
legged_control/legged_examples/legged_unitree/legged_unitree_hw
/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/cmake.lock /home/robofish/CM_DOG/devel/./cmake.lock
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/roseus/ros/legged_unitree_hw/manifest.l /home/robofish/CM_DOG/devel/share/roseus/ros/legged_unitree_hw/manifest.l
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/roseus/ros/legged_unitree_hw/msg/MotorFeedbackArray.l /home/robofish/CM_DOG/devel/share/roseus/ros/legged_unitree_hw/msg/MotorFeedbackArray.l
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/roseus/ros/legged_unitree_hw/msg/MotorFeedback.l /home/robofish/CM_DOG/devel/share/roseus/ros/legged_unitree_hw/msg/MotorFeedback.l
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/common-lisp/ros/legged_unitree_hw/msg/MotorFeedbackArray.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/legged_unitree_hw/msg/MotorFeedbackArray.lisp
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/common-lisp/ros/legged_unitree_hw/msg/_package.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/legged_unitree_hw/msg/_package.lisp
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/common-lisp/ros/legged_unitree_hw/msg/_package_MotorFeedbackArray.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/legged_unitree_hw/msg/_package_MotorFeedbackArray.lisp
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/common-lisp/ros/legged_unitree_hw/msg/MotorFeedback.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/legged_unitree_hw/msg/MotorFeedback.lisp
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/common-lisp/ros/legged_unitree_hw/msg/_package_MotorFeedback.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/legged_unitree_hw/msg/_package_MotorFeedback.lisp
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/common-lisp/ros/legged_unitree_hw/msg/legged_unitree_hw-msg.asd /home/robofish/CM_DOG/devel/share/common-lisp/ros/legged_unitree_hw/msg/legged_unitree_hw-msg.asd
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/gennodejs/ros/legged_unitree_hw/_index.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/legged_unitree_hw/_index.js
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/gennodejs/ros/legged_unitree_hw/msg/MotorFeedback.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/legged_unitree_hw/msg/MotorFeedback.js
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/gennodejs/ros/legged_unitree_hw/msg/_index.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/legged_unitree_hw/msg/_index.js
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/gennodejs/ros/legged_unitree_hw/msg/MotorFeedbackArray.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/legged_unitree_hw/msg/MotorFeedbackArray.js
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/legged_unitree_hw/cmake/legged_unitree_hw-msg-paths.cmake /home/robofish/CM_DOG/devel/share/legged_unitree_hw/cmake/legged_unitree_hw-msg-paths.cmake
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/legged_unitree_hw/cmake/legged_unitree_hw-msg-extras.cmake /home/robofish/CM_DOG/devel/share/legged_unitree_hw/cmake/legged_unitree_hw-msg-extras.cmake
/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/legged_unitree_hw/cmake/legged_unitree_hwConfig.cmake /home/robofish/CM_DOG/devel/share/legged_unitree_hw/cmake/legged_unitree_hwConfig.cmake
/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/share/legged_unitree_hw/cmake/legged_unitree_hwConfig-version.cmake /home/robofish/CM_DOG/devel/share/legged_unitree_hw/cmake/legged_unitree_hwConfig-version.cmake
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/include/legged_unitree_hw/MotorFeedback.h /home/robofish/CM_DOG/devel/include/legged_unitree_hw/MotorFeedback.h
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/include/legged_unitree_hw/MotorFeedbackArray.h /home/robofish/CM_DOG/devel/include/legged_unitree_hw/MotorFeedbackArray.h
/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/pkgconfig/legged_unitree_hw.pc /home/robofish/CM_DOG/devel/lib/pkgconfig/legged_unitree_hw.pc
/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/legged_unitree_hw/legged_unitree_hw_3_8_0 /home/robofish/CM_DOG/devel/lib/legged_unitree_hw/legged_unitree_hw_3_8_0
/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/legged_unitree_hw/legged_unitree_hw_3_3_1 /home/robofish/CM_DOG/devel/lib/legged_unitree_hw/legged_unitree_hw_3_3_1
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/python3/dist-packages/legged_unitree_hw/__init__.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/legged_unitree_hw/__init__.py
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/python3/dist-packages/legged_unitree_hw/msg/_MotorFeedback.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/legged_unitree_hw/msg/_MotorFeedback.py
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/python3/dist-packages/legged_unitree_hw/msg/_MotorFeedbackArray.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/legged_unitree_hw/msg/_MotorFeedbackArray.py
+/home/robofish/CM_DOG/devel/.private/legged_unitree_hw/lib/python3/dist-packages/legged_unitree_hw/msg/__init__.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/legged_unitree_hw/msg/__init__.py
diff --git a/.catkin_tools/profiles/default/packages/legged_unitree_hw/package.xml b/.catkin_tools/profiles/default/packages/legged_unitree_hw/package.xml
index 9787d44..05d1386 100644
--- a/.catkin_tools/profiles/default/packages/legged_unitree_hw/package.xml
+++ b/.catkin_tools/profiles/default/packages/legged_unitree_hw/package.xml
@@ -1,16 +1,25 @@
-
- legged_unitree_hw
- 0.0.0
- ROS control warped interface for Unitree Robots
- Qiayuan Liao
+ legged_unitree_hw
+ 0.0.0
+ The legged_unitree_hw package
- BSD
- Qiayuan Liao
+ user
- catkin
+ TODO
- cmake_clang_tools
- roscpp
- legged_hw
-
+ catkin
+
+ roscpp
+ legged_hw
+ message_generation
+ unitree_motor
+
+ roscpp
+ legged_hw
+ message_runtime
+ unitree_motor
+
+
+ catkin
+
+
\ No newline at end of file
diff --git a/.catkin_tools/profiles/default/packages/unitree_motor/devel_manifest.txt b/.catkin_tools/profiles/default/packages/unitree_motor/devel_manifest.txt
new file mode 100644
index 0000000..e7ea4bb
--- /dev/null
+++ b/.catkin_tools/profiles/default/packages/unitree_motor/devel_manifest.txt
@@ -0,0 +1,27 @@
+unitree_motor
+/home/robofish/CM_DOG/devel/.private/unitree_motor/cmake.lock /home/robofish/CM_DOG/devel/./cmake.lock
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/roseus/ros/unitree_motor/manifest.l /home/robofish/CM_DOG/devel/share/roseus/ros/unitree_motor/manifest.l
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/roseus/ros/unitree_motor/msg/MotorFeedbackArray.l /home/robofish/CM_DOG/devel/share/roseus/ros/unitree_motor/msg/MotorFeedbackArray.l
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/roseus/ros/unitree_motor/msg/MotorFeedback.l /home/robofish/CM_DOG/devel/share/roseus/ros/unitree_motor/msg/MotorFeedback.l
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/common-lisp/ros/unitree_motor/msg/MotorFeedbackArray.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/unitree_motor/msg/MotorFeedbackArray.lisp
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/common-lisp/ros/unitree_motor/msg/_package.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/unitree_motor/msg/_package.lisp
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/common-lisp/ros/unitree_motor/msg/_package_MotorFeedbackArray.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/unitree_motor/msg/_package_MotorFeedbackArray.lisp
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/common-lisp/ros/unitree_motor/msg/unitree_motor-msg.asd /home/robofish/CM_DOG/devel/share/common-lisp/ros/unitree_motor/msg/unitree_motor-msg.asd
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/common-lisp/ros/unitree_motor/msg/MotorFeedback.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/unitree_motor/msg/MotorFeedback.lisp
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/common-lisp/ros/unitree_motor/msg/_package_MotorFeedback.lisp /home/robofish/CM_DOG/devel/share/common-lisp/ros/unitree_motor/msg/_package_MotorFeedback.lisp
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/gennodejs/ros/unitree_motor/_index.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/unitree_motor/_index.js
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/gennodejs/ros/unitree_motor/msg/MotorFeedback.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/unitree_motor/msg/MotorFeedback.js
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/gennodejs/ros/unitree_motor/msg/_index.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/unitree_motor/msg/_index.js
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/gennodejs/ros/unitree_motor/msg/MotorFeedbackArray.js /home/robofish/CM_DOG/devel/share/gennodejs/ros/unitree_motor/msg/MotorFeedbackArray.js
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/unitree_motor/cmake/unitree_motor-msg-paths.cmake /home/robofish/CM_DOG/devel/share/unitree_motor/cmake/unitree_motor-msg-paths.cmake
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/unitree_motor/cmake/unitree_motor-msg-extras.cmake /home/robofish/CM_DOG/devel/share/unitree_motor/cmake/unitree_motor-msg-extras.cmake
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/unitree_motor/cmake/unitree_motorConfig-version.cmake /home/robofish/CM_DOG/devel/share/unitree_motor/cmake/unitree_motorConfig-version.cmake
+/home/robofish/CM_DOG/devel/.private/unitree_motor/share/unitree_motor/cmake/unitree_motorConfig.cmake /home/robofish/CM_DOG/devel/share/unitree_motor/cmake/unitree_motorConfig.cmake
+/home/robofish/CM_DOG/devel/.private/unitree_motor/include/unitree_motor/MotorFeedback.h /home/robofish/CM_DOG/devel/include/unitree_motor/MotorFeedback.h
+/home/robofish/CM_DOG/devel/.private/unitree_motor/include/unitree_motor/MotorFeedbackArray.h /home/robofish/CM_DOG/devel/include/unitree_motor/MotorFeedbackArray.h
+/home/robofish/CM_DOG/devel/.private/unitree_motor/lib/pkgconfig/unitree_motor.pc /home/robofish/CM_DOG/devel/lib/pkgconfig/unitree_motor.pc
+/home/robofish/CM_DOG/devel/.private/unitree_motor/lib/python3/dist-packages/unitree_motor/__init__.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/unitree_motor/__init__.py
+/home/robofish/CM_DOG/devel/.private/unitree_motor/lib/python3/dist-packages/unitree_motor/msg/_MotorFeedback.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/unitree_motor/msg/_MotorFeedback.py
+/home/robofish/CM_DOG/devel/.private/unitree_motor/lib/python3/dist-packages/unitree_motor/msg/_MotorFeedbackArray.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/unitree_motor/msg/_MotorFeedbackArray.py
+/home/robofish/CM_DOG/devel/.private/unitree_motor/lib/python3/dist-packages/unitree_motor/msg/__init__.py /home/robofish/CM_DOG/devel/lib/python3/dist-packages/unitree_motor/msg/__init__.py
+/home/robofish/CM_DOG/devel/.private/unitree_motor/lib/unitree_motor/unitree_motor /home/robofish/CM_DOG/devel/lib/unitree_motor/unitree_motor
diff --git a/.catkin_tools/profiles/default/packages/unitree_motor/package.xml b/.catkin_tools/profiles/default/packages/unitree_motor/package.xml
new file mode 100644
index 0000000..2e91ad7
--- /dev/null
+++ b/.catkin_tools/profiles/default/packages/unitree_motor/package.xml
@@ -0,0 +1,26 @@
+
+
+ unitree_motor
+ 0.0.0
+ The unitree_motor package
+
+ user
+
+ TODO
+
+ catkin
+
+ roscpp
+ rospy
+ std_msgs
+ message_generation
+
+ roscpp
+ rospy
+ std_msgs
+ message_runtime
+
+
+
+
+
\ No newline at end of file
diff --git a/build.sh b/build.sh
index ac55bbb..63f04cc 100644
--- a/build.sh
+++ b/build.sh
@@ -1,11 +1,13 @@
# 编译`ocs2_legged_robot_ros`包
catkin config -DCMAKE_BUILD_TYPE=RelWithDebInfo
-catkin build ocs2_legged_robot_ros ocs2_self_collision_visualization
+# catkin build ocs2_legged_robot_ros ocs2_self_collision_visualization
# 构建`legged_control`的源代码:
-catkin build legged_controllers legged_unitree_description
+# catkin build legged_controllers legged_unitree_description
# 构建模拟
-catkin build legged_gazebo
+# catkin build legged_gazebo
# 构建实际硬件接口机器人
catkin build legged_unitree_hw
# 构建外置N100imu
-catkin build fdilink_ahrs
\ No newline at end of file
+catkin build fdilink_ahrs
+#构建电机控制和反馈
+catkin build unitree_motor
\ No newline at end of file
diff --git a/src/fdilink_ahrs/launch/ahrs_data.launch b/src/fdilink_ahrs/launch/ahrs_data.launch
index 57c743b..5c8b7d5 100644
--- a/src/fdilink_ahrs/launch/ahrs_data.launch
+++ b/src/fdilink_ahrs/launch/ahrs_data.launch
@@ -3,7 +3,7 @@
-
+
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/CMakeLists.txt b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/CMakeLists.txt
index 8d16f62..754e489 100644
--- a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/CMakeLists.txt
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/CMakeLists.txt
@@ -7,6 +7,20 @@ find_package(catkin REQUIRED
COMPONENTS
roscpp
legged_hw
+ message_generation
+ unitree_motor
+)
+
+add_message_files(
+ FILES
+ MotorFeedback.msg
+ MotorFeedbackArray.msg
+)
+
+generate_messages(
+ DEPENDENCIES
+ std_msgs
+ unitree_motor
)
catkin_package(
@@ -15,6 +29,7 @@ catkin_package(
CATKIN_DEPENDS
roscpp
legged_hw
+ message_runtime
)
###########
@@ -52,6 +67,9 @@ target_link_libraries(${PROJECT_NAME}_3_8_0
libunitree_legged_sdk_amd64_3_8_0.a
)
+add_dependencies(${PROJECT_NAME}_3_3_1 ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+add_dependencies(${PROJECT_NAME}_3_8_0 ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
#########################
### CLANG TOOLING ###
#########################
@@ -87,4 +105,4 @@ install(DIRECTORY include/${PROJECT_NAME}_3_3_1/ include/${PROJECT_NAME}_3_8_0/
# Mark other files for installation
install(DIRECTORY config launch lib
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
- )
+ )
\ No newline at end of file
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/config/a1.yaml b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/config/a1.yaml
index b4ae9e8..8f7b93d 100644
--- a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/config/a1.yaml
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/config/a1.yaml
@@ -1,6 +1,6 @@
legged_unitree_hw:
- loop_frequency: 500
- cycle_time_error_threshold: 0.002
- thread_priority: 95
- power_limit: 4
- contact_threshold: 40
+ loop_frequency: 500
+ cycle_time_error_threshold: 0.002
+ thread_priority: 95
+ power_limit: 4
+ contact_threshold: 40
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/include/legged_unitree_hw/UnitreeHW.h b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/include/legged_unitree_hw/UnitreeHW.h
index 9c0b8c7..9514404 100644
--- a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/include/legged_unitree_hw/UnitreeHW.h
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/include/legged_unitree_hw/UnitreeHW.h
@@ -7,6 +7,8 @@
#include
#include // 确保包含这个头文件
+#include "legged_unitree_hw/MotorFeedback.h"
+#include "legged_unitree_hw/MotorFeedbackArray.h"
#ifdef UNITREE_SDK_3_3_1
#include "unitree_legged_sdk_3_3_1/safety.h"
@@ -16,6 +18,7 @@
#include "unitree_legged_sdk_3_8_0/udp.h"
#endif
+
namespace legged {
const std::vector CONTACT_SENSOR_NAMES = {"RF_FOOT", "LF_FOOT", "RH_FOOT", "LH_FOOT"};
@@ -69,6 +72,7 @@ class UnitreeHW : public LeggedHW {
void updateJoystick(const ros::Time& time);
void updateContact(const ros::Time& time);
+ void motorFeedbackCallback(const legged_unitree_hw::MotorFeedbackArray::ConstPtr& msg);
private:
void imuCallback(const sensor_msgs::Imu::ConstPtr& imuMsg);
@@ -87,6 +91,8 @@ class UnitreeHW : public LeggedHW {
sensor_msgs::Imu::ConstPtr lastImuMsg_;
UnitreeMotorData jointData_[12]{}; // NOLINT(modernize-avoid-c-arrays)
UnitreeImuData imuData_{};
+ ros::Subscriber motorFeedbackSub_;
+ legged_unitree_hw::MotorFeedbackArray motorFeedbackArray_;
bool contactState_[4]{}; // NOLINT(modernize-avoid-c-arrays)
sensor_msgs::Imu imuDataMsg_;
int powerLimit_{};
@@ -97,4 +103,4 @@ class UnitreeHW : public LeggedHW {
ros::Time lastJoyPub_, lastContactPub_;
};
-} // namespace legged
+} // namespace legged
\ No newline at end of file
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedback.msg b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedback.msg
new file mode 100644
index 0000000..62b54ce
--- /dev/null
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedback.msg
@@ -0,0 +1,6 @@
+int32 id
+float32 tau
+float32 pos
+float32 vel
+int32 temp
+int32 merror
\ No newline at end of file
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedbackArray.msg b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedbackArray.msg
new file mode 100644
index 0000000..afdea52
--- /dev/null
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/msg/MotorFeedbackArray.msg
@@ -0,0 +1 @@
+unitree_motor/MotorFeedback[] motors
\ No newline at end of file
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/package.xml b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/package.xml
index 9787d44..05d1386 100644
--- a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/package.xml
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/package.xml
@@ -1,16 +1,25 @@
-
- legged_unitree_hw
- 0.0.0
- ROS control warped interface for Unitree Robots
- Qiayuan Liao
+ legged_unitree_hw
+ 0.0.0
+ The legged_unitree_hw package
- BSD
- Qiayuan Liao
+ user
- catkin
+ TODO
- cmake_clang_tools
- roscpp
- legged_hw
-
+ catkin
+
+ roscpp
+ legged_hw
+ message_generation
+ unitree_motor
+
+ roscpp
+ legged_hw
+ message_runtime
+ unitree_motor
+
+
+ catkin
+
+
\ No newline at end of file
diff --git a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/src/UnitreeHW.cpp b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/src/UnitreeHW.cpp
index 16e9e95..e6a734e 100644
--- a/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/src/UnitreeHW.cpp
+++ b/src/legged_control/legged_examples/legged_unitree/legged_unitree_hw/src/UnitreeHW.cpp
@@ -5,6 +5,9 @@
#include "legged_unitree_hw/UnitreeHW.h"
#include // 确保包含这个头文件
+#include "legged_unitree_hw/MotorFeedback.h"
+#include "legged_unitree_hw/MotorFeedbackArray.h"
+
#ifdef UNITREE_SDK_3_3_1
#include "unitree_legged_sdk_3_3_1/unitree_joystick.h"
#elif UNITREE_SDK_3_8_0
@@ -57,46 +60,55 @@ bool UnitreeHW::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) {
joyPublisher_ = root_nh.advertise("/joy", 10);
contactPublisher_ = root_nh.advertise(std::string("/contact"), 10);
imuSubscriber_ = root_nh.subscribe("/imu", 10, &UnitreeHW::imuCallback, this);
-
+ motorFeedbackSub_ = root_nh.subscribe("motor_feedback", 10, &UnitreeHW::motorFeedbackCallback, this);
return true;
}
void UnitreeHW::imuCallback(const sensor_msgs::Imu::ConstPtr& imuMsg) {
lastImuMsg_ = imuMsg;
}
-
+void UnitreeHW::motorFeedbackCallback(const legged_unitree_hw::MotorFeedbackArray::ConstPtr& msg) {
+ motorFeedbackArray_ = *msg;
+}
void UnitreeHW::read(const ros::Time& time, const ros::Duration& /*period*/) {
// 模拟接收数据
// udp_->Recv();
// udp_->GetRecv(lowState_);
// 模拟数据
- for (int i = 0; i < 12; ++i) {
- // lowState_.motorState[i].q = static_cast(i * 0.1); // 模拟位置
- // lowState_.motorState[i].dq = static_cast(i * 0.01); // 模拟速度
- // lowState_.motorState[i].tauEst = static_cast(i * 0.001); // 模拟力矩
- lowState_.motorState[i].q = 0.0; // 模拟位置
- lowState_.motorState[i].dq = 0.0; // 模拟速度
- lowState_.motorState[i].tauEst = 0.0; // 模拟力矩
+ // for (int i = 0; i < 12; ++i) {
+ // lowState_.motorState[i].q = 0.0; // 模拟位置
+ // lowState_.motorState[i].dq = 0.0; // 模拟速度
+ // lowState_.motorState[i].tauEst = 0.0; // 模拟力矩
+ // }
+
+ // 从 motor_feedback 话题获取数据
+ if (!motorFeedbackArray_.motors.empty()) {
+ for (const auto& motor : motorFeedbackArray_.motors) {
+ if (motor.id < 12) {
+ lowState_.motorState[motor.id].q = motor.pos;
+ lowState_.motorState[motor.id].dq = motor.vel;
+ lowState_.motorState[motor.id].tauEst = motor.tau;
+ }
+ }
}
// 读取 /imu 话题的数据
if (lastImuMsg_) {
- lowState_.imu.quaternion[0] = lastImuMsg_->orientation.w;
- lowState_.imu.quaternion[1] = lastImuMsg_->orientation.x;
- lowState_.imu.quaternion[2] = lastImuMsg_->orientation.y;
- lowState_.imu.quaternion[3] = lastImuMsg_->orientation.z;
- lowState_.imu.gyroscope[0] = lastImuMsg_->angular_velocity.x;
- lowState_.imu.gyroscope[1] = lastImuMsg_->angular_velocity.y;
- lowState_.imu.gyroscope[2] = lastImuMsg_->angular_velocity.z;
- lowState_.imu.accelerometer[0] = lastImuMsg_->linear_acceleration.x;
- lowState_.imu.accelerometer[1] = lastImuMsg_->linear_acceleration.y;
- lowState_.imu.accelerometer[2] = lastImuMsg_->linear_acceleration.z;
+ const auto& ori = lastImuMsg_->orientation;
+ const auto& ang_vel = lastImuMsg_->angular_velocity;
+ const auto& lin_acc = lastImuMsg_->linear_acceleration;
- // 打印接收到的数据
- ROS_INFO("imuMsg->orientation.w: %f", lastImuMsg_->orientation.w);
- } else {
- ROS_WARN("Failed to receive IMU data");
+ lowState_.imu.quaternion[0] = ori.w;
+ lowState_.imu.quaternion[1] = ori.x;
+ lowState_.imu.quaternion[2] = ori.y;
+ lowState_.imu.quaternion[3] = ori.z;
+ lowState_.imu.gyroscope[0] = ang_vel.x;
+ lowState_.imu.gyroscope[1] = ang_vel.y;
+ lowState_.imu.gyroscope[2] = ang_vel.z;
+ lowState_.imu.accelerometer[0] = lin_acc.x;
+ lowState_.imu.accelerometer[1] = lin_acc.y;
+ lowState_.imu.accelerometer[2] = lin_acc.z;
}
for (size_t i = 0; i < CONTACT_SENSOR_NAMES.size(); ++i) {
@@ -125,7 +137,7 @@ void UnitreeHW::read(const ros::Time& time, const ros::Duration& /*period*/) {
}
// 设置前馈和期望速度为零,以避免在未设置控制器 setCommand 时出现安全问题
- std::vector names = hybridJointInterface_.getNames();
+ const auto& names = hybridJointInterface_.getNames();
for (const auto& name : names) {
HybridJointHandle handle = hybridJointInterface_.getHandle(name);
handle.setFeedforward(0.);
diff --git a/src/unitree_motor/CMakeLists.txt b/src/unitree_motor/CMakeLists.txt
new file mode 100644
index 0000000..9ad29e3
--- /dev/null
+++ b/src/unitree_motor/CMakeLists.txt
@@ -0,0 +1,47 @@
+# filepath: /home/robofish/motor_control/src/unitree_motor/CMakeLists.txt
+cmake_minimum_required(VERSION 3.1.0)
+project(unitree_motor)
+
+find_package(catkin REQUIRED COMPONENTS
+ roscpp
+ rospy
+ std_msgs
+ message_generation
+)
+
+add_message_files(
+ FILES
+ MotorFeedback.msg
+ MotorFeedbackArray.msg
+)
+
+generate_messages(
+ DEPENDENCIES
+ std_msgs
+)
+
+catkin_package(
+ CATKIN_DEPENDS message_runtime
+)
+
+include_directories(
+ include
+ ${catkin_INCLUDE_DIRS}
+)
+
+link_directories(lib)
+
+if(CMAKE_HOST_SYSTEM_PROCESSOR MATCHES "aarch64")
+ set(EXTRA_LIBS libUnitreeMotorSDK_Arm64.so)
+else()
+ set(EXTRA_LIBS libUnitreeMotorSDK_Linux64.so)
+endif()
+
+# 添加launch
+install(DIRECTORY launch/
+ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
+)
+
+add_executable(unitree_motor src/unitree_motor.cpp)
+add_dependencies(unitree_motor ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+target_link_libraries(unitree_motor ${catkin_LIBRARIES} ${EXTRA_LIBS})
\ No newline at end of file
diff --git a/src/unitree_motor/README.md b/src/unitree_motor/README.md
new file mode 100644
index 0000000..a208c0a
--- /dev/null
+++ b/src/unitree_motor/README.md
@@ -0,0 +1,3 @@
+# unitree_motor
+
+包含了宇数电机的控制和接收反馈功能
\ No newline at end of file
diff --git a/src/unitree_motor/include/IOPort/IOPort.h b/src/unitree_motor/include/IOPort/IOPort.h
new file mode 100755
index 0000000..173b617
--- /dev/null
+++ b/src/unitree_motor/include/IOPort/IOPort.h
@@ -0,0 +1,41 @@
+#ifndef __IOPORT_H
+#define __IOPORT_H
+
+#include
+#include
+#include
+#include "unitreeMotor/unitreeMotor.h"
+
+enum class BlockYN{
+ YES,
+ NO
+};
+
+class IOPort{
+public:
+ IOPort(BlockYN blockYN, size_t recvLength, size_t timeOutUs){
+ resetIO(blockYN, recvLength, timeOutUs);
+ }
+ virtual ~IOPort(){}
+ virtual size_t send(uint8_t *sendMsg, size_t sendLength) = 0;
+ virtual size_t recv(uint8_t *recvMsg, size_t recvLength) = 0;
+ virtual size_t recv(uint8_t *recvMsg) = 0;
+ virtual bool sendRecv(std::vector &sendVec, std::vector &recvVec) = 0;
+ void resetIO(BlockYN blockYN, size_t recvLength, size_t timeOutUs);
+protected:
+ BlockYN _blockYN = BlockYN::NO;
+ size_t _recvLength;
+ timeval _timeout;
+ timeval _timeoutSaved;
+};
+
+inline void IOPort::resetIO(BlockYN blockYN, size_t recvLength, size_t timeOutUs){
+ _blockYN = blockYN;
+ _recvLength = recvLength;
+ _timeout.tv_sec = timeOutUs / 1000000;
+ _timeout.tv_usec = timeOutUs % 1000000;
+ _timeoutSaved = _timeout;
+}
+
+
+#endif // z1_lib_IOPORT_H
\ No newline at end of file
diff --git a/src/unitree_motor/include/crc/crc32.h b/src/unitree_motor/include/crc/crc32.h
new file mode 100755
index 0000000..cea99c8
--- /dev/null
+++ b/src/unitree_motor/include/crc/crc32.h
@@ -0,0 +1,33 @@
+#ifndef CRC32_H
+#define CRC32_H
+
+#include
+
+inline uint32_t crc32_core(uint32_t* ptr, uint32_t len){
+ uint32_t xbit = 0;
+ uint32_t data = 0;
+ uint32_t CRC32 = 0xFFFFFFFF;
+ const uint32_t dwPolynomial = 0x04c11db7;
+ for (uint32_t i = 0; i < len; i++)
+ {
+ xbit = 1 << 31;
+ data = ptr[i];
+ for (uint32_t bits = 0; bits < 32; bits++)
+ {
+ if (CRC32 & 0x80000000)
+ {
+ CRC32 <<= 1;
+ CRC32 ^= dwPolynomial;
+ }
+ else
+ CRC32 <<= 1;
+ if (data & xbit)
+ CRC32 ^= dwPolynomial;
+
+ xbit >>= 1;
+ }
+ }
+ return CRC32;
+}
+
+#endif // CRC32_H
\ No newline at end of file
diff --git a/src/unitree_motor/include/crc/crc_ccitt.h b/src/unitree_motor/include/crc/crc_ccitt.h
new file mode 100644
index 0000000..2930e24
--- /dev/null
+++ b/src/unitree_motor/include/crc/crc_ccitt.h
@@ -0,0 +1,67 @@
+#ifndef __CRC_CCITT_H
+#define __CRC_CCITT_H
+
+/*
+ * This mysterious table is just the CRC of each possible byte. It can be
+ * computed using the standard bit-at-a-time methods. The polynomial can
+ * be seen in entry 128, 0x8408. This corresponds to x^0 + x^5 + x^12.
+ * Add the implicit x^16, and you have the standard CRC-CCITT.
+ * https://github.com/torvalds/linux/blob/5bfc75d92efd494db37f5c4c173d3639d4772966/lib/crc-ccitt.c
+ */
+uint16_t const crc_ccitt_table[256] = {
+ 0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf,
+ 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7,
+ 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e,
+ 0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876,
+ 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd,
+ 0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5,
+ 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c,
+ 0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974,
+ 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb,
+ 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3,
+ 0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a,
+ 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72,
+ 0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9,
+ 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1,
+ 0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738,
+ 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70,
+ 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7,
+ 0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff,
+ 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036,
+ 0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e,
+ 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5,
+ 0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd,
+ 0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134,
+ 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c,
+ 0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3,
+ 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb,
+ 0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232,
+ 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a,
+ 0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1,
+ 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9,
+ 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330,
+ 0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78
+};
+
+
+static uint16_t crc_ccitt_byte(uint16_t crc, const uint8_t c)
+{
+ return (crc >> 8) ^ crc_ccitt_table[(crc ^ c) & 0xff];
+}
+
+/**
+ * crc_ccitt - recompute the CRC (CRC-CCITT variant) for the data
+ * buffer
+ * @crc: previous CRC value
+ * @buffer: data pointer
+ * @len: number of bytes in the buffer
+ */
+inline uint16_t crc_ccitt(uint16_t crc, uint8_t const *buffer, size_t len)
+{
+ while (len--)
+ crc = crc_ccitt_byte(crc, *buffer++);
+ return crc;
+}
+
+
+#endif
diff --git a/src/unitree_motor/include/serialPort/SerialPort.h b/src/unitree_motor/include/serialPort/SerialPort.h
new file mode 100755
index 0000000..0f608b2
--- /dev/null
+++ b/src/unitree_motor/include/serialPort/SerialPort.h
@@ -0,0 +1,98 @@
+#ifndef __SERIALPORT_H
+#define __SERIALPORT_H
+
+/*
+High frequency serial communication,
+Not that common, but useful for motor communication.
+*/
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "serialPort/include/errorClass.h"
+#include "unitreeMotor/unitreeMotor.h"
+#include "IOPort/IOPort.h"
+
+enum class bytesize_t{
+ fivebits,
+ sixbits,
+ sevenbits,
+ eightbits
+};
+
+enum class parity_t{
+ parity_none,
+ parity_odd,
+ parity_even,
+ parity_mark,
+ parity_space
+};
+
+enum class stopbits_t{
+ stopbits_one,
+ stopbits_two,
+ stopbits_one_point_five
+};
+
+enum class flowcontrol_t{
+ flowcontrol_none,
+ flowcontrol_software,
+ flowcontrol_hardware
+};
+
+class SerialPort : public IOPort{
+public:
+ SerialPort(const std::string &portName,
+ size_t recvLength = 16,
+ uint32_t baudrate = 4000000,
+ size_t timeOutUs = 20000,
+ BlockYN blockYN = BlockYN::NO,
+ bytesize_t bytesize = bytesize_t::eightbits,
+ parity_t parity = parity_t::parity_none,
+ stopbits_t stopbits = stopbits_t::stopbits_one,
+ flowcontrol_t flowcontrol = flowcontrol_t::flowcontrol_none);
+ virtual ~SerialPort();
+ void resetSerial(size_t recvLength = 16,
+ uint32_t baudrate = 4000000,
+ size_t timeOutUs = 20000,
+ BlockYN blockYN = BlockYN::NO,
+ bytesize_t bytesize = bytesize_t::eightbits,
+ parity_t parity = parity_t::parity_none,
+ stopbits_t stopbits = stopbits_t::stopbits_one,
+ flowcontrol_t flowcontrol = flowcontrol_t::flowcontrol_none);
+ size_t send(uint8_t *sendMsg, size_t sendLength);
+ size_t recv(uint8_t *recvMsg, size_t recvLength);
+ size_t recv(uint8_t *recvMsg);
+ bool sendRecv(uint8_t *sendMsg, uint8_t *recvMsg, size_t sendLength);
+ bool sendRecv(MotorCmd* sendMsg, MotorData* recvMsg);
+ bool sendRecv(std::vector &sendVec, std::vector &recvVec);
+ void test();
+private:
+ void _open();
+ void _set();
+ void _close();
+ size_t _nonBlockRecv(uint8_t *recvMsg, size_t readLen);
+ std::string _portName;
+ uint32_t _baudrate;
+ bytesize_t _bytesize;
+ parity_t _parity;
+ stopbits_t _stopbits;
+ flowcontrol_t _flowcontrol;
+ bool _xonxoff;
+ bool _rtscts;
+ int _fd;
+ fd_set _rSet;
+
+};
+
+
+
+
+#endif // SERIALPORT_H
\ No newline at end of file
diff --git a/src/unitree_motor/include/serialPort/include/errorClass.h b/src/unitree_motor/include/serialPort/include/errorClass.h
new file mode 100755
index 0000000..48313c3
--- /dev/null
+++ b/src/unitree_motor/include/serialPort/include/errorClass.h
@@ -0,0 +1,52 @@
+#ifndef __ERRORCLASS_H
+#define __ERRORCLASS_H
+
+#include
+#include
+#include
+#include
+#include
+
+#define THROW(exceptionClass, message) throw exceptionClass(__FILE__, \
+__LINE__, (message) )
+
+class IOException : public std::exception
+{
+ // Disable copy constructors
+ IOException& operator=(const IOException&);
+ std::string file_;
+ int line_;
+ std::string e_what_;
+ int errno_;
+public:
+ explicit IOException (std::string file, int line, int errnum)
+ : file_(file), line_(line), errno_(errnum) {
+ std::stringstream ss;
+#if defined(_WIN32) && !defined(__MINGW32__)
+ char error_str [1024];
+ strerror_s(error_str, 1024, errnum);
+#else
+ char * error_str = strerror(errnum);
+#endif
+ ss << "IO Exception (" << errno_ << "): " << error_str;
+ ss << ", file " << file_ << ", line " << line_ << ".";
+ e_what_ = ss.str();
+ }
+ explicit IOException (std::string file, int line, const char * description)
+ : file_(file), line_(line), errno_(0) {
+ std::stringstream ss;
+ ss << "IO Exception: " << description;
+ ss << ", file " << file_ << ", line " << line_ << ".";
+ e_what_ = ss.str();
+ }
+ virtual ~IOException() throw() {}
+ IOException (const IOException& other) : line_(other.line_), e_what_(other.e_what_), errno_(other.errno_) {}
+
+ int getErrorNumber () const { return errno_; }
+
+ virtual const char* what () const throw () {
+ return e_what_.c_str();
+ }
+};
+
+#endif // ERRORCLASS_H
\ No newline at end of file
diff --git a/src/unitree_motor/include/unitreeMotor/include/motor_msg_A1B1.h b/src/unitree_motor/include/unitreeMotor/include/motor_msg_A1B1.h
new file mode 100755
index 0000000..95120ab
--- /dev/null
+++ b/src/unitree_motor/include/unitreeMotor/include/motor_msg_A1B1.h
@@ -0,0 +1,162 @@
+#ifndef MOTOR_A1B1_MSG
+#define MOTOR_A1B1_MSG
+
+#include
+typedef int16_t q15_t;
+
+#pragma pack(1)
+
+// 发送用单个数据数据结构
+typedef union{
+ int32_t L;
+ uint8_t u8[4];
+ uint16_t u16[2];
+ uint32_t u32;
+ float F;
+}COMData32;
+
+typedef struct {
+ // 定义 数据包头
+ unsigned char start[2]; // 包头
+ unsigned char motorID; // 电机ID 0,1,2,3 ... 0xBB 表示向所有电机广播(此时无返回)
+ unsigned char reserved;
+}COMHead;
+
+#pragma pack()
+
+#pragma pack(1)
+
+typedef struct {
+
+ uint8_t fan_d; // 关节上的散热风扇转速
+ uint8_t Fmusic; // 电机发声频率 /64*1000 15.625f 频率分度
+ uint8_t Hmusic; // 电机发声强度 推荐值4 声音强度 0.1 分度
+ uint8_t reserved4;
+
+ uint8_t FRGB[4]; // 足端LED
+
+}LowHzMotorCmd;
+
+typedef struct { // 以 4个字节一组排列 ,不然编译器会凑整
+ // 定义 数据
+ uint8_t mode; // 关节模式选择
+ uint8_t ModifyBit; // 电机控制参数修改位
+ uint8_t ReadBit; // 电机控制参数发送位
+ uint8_t reserved;
+
+ COMData32 Modify; // 电机参数修改 的数据
+ //实际给FOC的指令力矩为:
+ //K_P*delta_Pos + K_W*delta_W + T
+ q15_t T; // 期望关节的输出力矩(电机本身的力矩)x256, 7 + 8 描述
+ q15_t W; // 期望关节速度 (电机本身的速度) x128, 8 + 7描述
+ int32_t Pos; // 期望关节位置 x 16384/6.2832, 14位编码器(主控0点修正,电机关节还是以编码器0点为准)
+
+ q15_t K_P; // 关节刚度系数 x2048 4+11 描述
+ q15_t K_W; // 关节速度系数 x1024 5+10 描述
+
+ uint8_t LowHzMotorCmdIndex; // 电机低频率控制命令的索引, 0-7, 分别代表LowHzMotorCmd中的8个字节
+ uint8_t LowHzMotorCmdByte; // 电机低频率控制命令的字节
+
+ COMData32 Res[1]; // 通讯 保留字节 用于实现别的一些通讯内容
+
+}MasterComdV3; // 加上数据包的包头 和CRC 34字节
+
+typedef struct {
+ // 定义 电机控制命令数据包
+ COMHead head;
+ MasterComdV3 Mdata;
+ COMData32 CRCdata;
+}MasterComdDataV3;//返回数据
+
+// typedef struct {
+// // 定义 总得485 数据包
+
+// MasterComdData M1;
+// MasterComdData M2;
+// MasterComdData M3;
+
+// }DMA485TxDataV3;
+
+#pragma pack()
+
+#pragma pack(1)
+
+typedef struct { // 以 4个字节一组排列 ,不然编译器会凑整
+ // 定义 数据
+ uint8_t mode; // 当前关节模式
+ uint8_t ReadBit; // 电机控制参数修改 是否成功位
+ int8_t Temp; // 电机当前平均温度
+ uint8_t MError; // 电机错误 标识
+
+ COMData32 Read; // 读取的当前 电机 的控制数据
+ int16_t T; // 当前实际电机输出力矩 7 + 8 描述
+
+ int16_t W; // 当前实际电机速度(高速) 8 + 7 描述
+ float LW; // 当前实际电机速度(低速)
+
+ int16_t W2; // 当前实际关节速度(高速) 8 + 7 描述
+ float LW2; // 当前实际关节速度(低速)
+
+ int16_t Acc; // 电机转子加速度 15+0 描述 惯量较小
+ int16_t OutAcc; // 输出轴加速度 12+3 描述 惯量较大
+
+ int32_t Pos; // 当前电机位置(主控0点修正,电机关节还是以编码器0点为准)
+ int32_t Pos2; // 关节编码器位置(输出编码器)
+
+ int16_t gyro[3]; // 电机驱动板6轴传感器数据
+ int16_t acc[3];
+
+ // 力传感器的数据
+ int16_t Fgyro[3]; //
+ int16_t Facc[3];
+ int16_t Fmag[3];
+ uint8_t Ftemp; // 8位表示的温度 7位(-28~100度) 1位0.5度分辨率
+
+ int16_t Force16; // 力传感器高16位数据
+ int8_t Force8; // 力传感器低8位数据
+
+ uint8_t FError; // 足端传感器错误标识
+
+ int8_t Res[1]; // 通讯 保留字节
+
+}ServoComdV3; // 加上数据包的包头 和CRC 78字节(4+70+4)
+
+typedef struct {
+ // 定义 电机控制命令数据包
+ COMHead head;
+ ServoComdV3 Mdata;
+
+ COMData32 CRCdata;
+
+}ServoComdDataV3; //发送数据
+
+// typedef struct {
+// // 定义 总的485 接受数据包
+
+// ServoComdDataV3 M[3];
+// // uint8_t nullbyte1;
+
+// }DMA485RxDataV3;
+
+
+#pragma pack()
+
+// 00 00 00 00 00
+// 00 00 00 00 00
+// 00 00 00 00 00
+// 00 00 00
+// 数据包默认初始化
+// 主机发送的数据包
+/*
+ Tx485Data[_FR][i].head.start[0] = 0xFE ; Tx485Data[_FR][i].head.start[1] = 0xEE; // 数据包头
+ Tx485Data[_FR][i].Mdata.ModifyBit = 0xFF; Tx485Data[_FR][i].Mdata.mode = 0; // 默认不修改数据 和 电机的默认工作模式
+ Tx485Data[_FR][i].head.motorID = i; 0 // 目标电机标号
+ Tx485Data[_FR][i].Mdata.T = 0.0f; // 默认目标关节输出力矩 motor1.Extra_Torque = motorRxData[1].Mdata.T*0.390625f; // N.M 转化为 N.CM IQ8描述
+ Tx485Data[_FR][i].Mdata.Pos = 0x7FE95C80; // 默认目标关节位置 不启用位置环 14位分辨率
+ Tx485Data[_FR][i].Mdata.W = 16000.0f; // 默认目标关节速度 不启用速度环 1+8+7描述 motor1.Target_Speed = motorRxData[1].Mdata.W*0.0078125f; // 单位 rad/s IQ7描述
+ Tx485Data[_FR][i].Mdata.K_P = (q15_t)(0.6f*(1<<11)); // 默认关节刚度系数 4+11 描述 motor1.K_Pos = ((float)motorRxData[1].Mdata.K_P)/(1<<11); // 描述刚度的通讯数据格式 4+11
+ Tx485Data[_FR][i].Mdata.K_W = (q15_t)(1.0f*(1<<10)); // 默认关节速度系数 5+10 描述 motor1.K_Speed = ((float)motorRxData[1].Mdata.K_W)/(1<<10); // 描述阻尼的通讯数据格式 5+10
+*/
+
+
+#endif
\ No newline at end of file
diff --git a/src/unitree_motor/include/unitreeMotor/include/motor_msg_GO-M8010-6.h b/src/unitree_motor/include/unitreeMotor/include/motor_msg_GO-M8010-6.h
new file mode 100755
index 0000000..54aeefe
--- /dev/null
+++ b/src/unitree_motor/include/unitreeMotor/include/motor_msg_GO-M8010-6.h
@@ -0,0 +1,90 @@
+#ifndef __MOTOR_MSG_GO_M8010_6_H
+#define __MOTOR_MSG_GO_M8010_6_H
+
+#include
+#define CRC_SIZE 2
+#define CTRL_DAT_SIZE sizeof(ControlData_t) - CRC_SIZE
+#define DATA_DAT_SIZE sizeof(MotorData_t) - CRC_SIZE
+
+#pragma pack(1)
+
+/**
+ * @brief 电机模式控制信息
+ *
+ */
+typedef struct
+{
+ uint8_t id :4; // 电机ID: 0,1...,14 15表示向所有电机广播数据(此时无返回)
+ uint8_t status :3; // 工作模式: 0.锁定 1.FOC闭环 2.编码器校准 3.保留
+ uint8_t none :1; // 保留位
+} RIS_Mode_t; // 控制模式 1Byte
+
+/**
+ * @brief 电机状态控制信息
+ *
+ */
+typedef struct
+{
+ int16_t tor_des; // 期望关节输出扭矩 unit: N.m (q8)
+ int16_t spd_des; // 期望关节输出速度 unit: rad/s (q7)
+ int32_t pos_des; // 期望关节输出位置 unit: rad (q15)
+ uint16_t k_pos; // 期望关节刚度系数 unit: 0.0-1.0 (q15)
+ uint16_t k_spd; // 期望关节阻尼系数 unit: 0.0-1.0 (q15)
+
+} RIS_Comd_t; // 控制参数 12Byte
+
+/**
+ * @brief 电机状态反馈信息
+ *
+ */
+typedef struct
+{
+ int16_t torque; // 实际关节输出扭矩 unit: N.m (q8)
+ int16_t speed; // 实际关节输出速度 unit: rad/s (q7)
+ int32_t pos; // 实际关节输出位置 unit: W (q15)
+ int8_t temp; // 电机温度: -128~127°C 90°C时触发温度保护
+ uint8_t MError :3; // 电机错误标识: 0.正常 1.过热 2.过流 3.过压 4.编码器故障 5-7.保留
+ uint16_t force :12; // 足端气压传感器数据 12bit (0-4095)
+ uint8_t none :1; // 保留位
+} RIS_Fbk_t; // 状态数据 11Byte
+
+
+#pragma pack()
+
+#pragma pack(1)
+
+/**
+ * @brief 控制数据包格式
+ *
+ */
+typedef struct
+{
+ uint8_t head[2]; // 包头 2Byte
+ RIS_Mode_t mode; // 电机控制模式 1Byte
+ RIS_Comd_t comd; // 电机期望数据 12Byte
+ uint16_t CRC16; // CRC 2Byte
+
+} ControlData_t; // 主机控制命令 17Byte
+
+/**
+ * @brief 电机反馈数据包格式
+ *
+ */
+typedef struct
+{
+ uint8_t head[2]; // 包头 2Byte
+ RIS_Mode_t mode; // 电机控制模式 1Byte
+ RIS_Fbk_t fbk; // 电机反馈数据 11Byte
+ uint16_t CRC16; // CRC 2Byte
+
+} MotorData_t; // 电机返回数据 16Byte
+
+#pragma pack()
+
+#endif
+
+
+
+
+
+
diff --git a/src/unitree_motor/include/unitreeMotor/unitreeMotor.h b/src/unitree_motor/include/unitreeMotor/unitreeMotor.h
new file mode 100755
index 0000000..fbce3de
--- /dev/null
+++ b/src/unitree_motor/include/unitreeMotor/unitreeMotor.h
@@ -0,0 +1,74 @@
+#ifndef __UNITREEMOTOR_H
+#define __UNITREEMOTOR_H
+
+#include "unitreeMotor/include/motor_msg_GO-M8010-6.h"
+#include "unitreeMotor/include/motor_msg_A1B1.h"
+#include
+#include
+
+enum class MotorType{
+ A1, // 4.8M baudrate
+ B1, // 6.0M baudrate
+ GO_M8010_6
+};
+
+enum class MotorMode{
+ BRAKE,
+ FOC,
+ CALIBRATE
+};
+
+struct MotorCmd{
+ public:
+ MotorCmd(){}
+ MotorType motorType;
+ int hex_len;
+ unsigned short id;
+ unsigned short mode;
+ float tau;
+ float dq;
+ float q;
+ float kp;
+ float kd;
+
+ void modify_data(MotorCmd* motor_s);
+ uint8_t* get_motor_send_data();
+
+ COMData32 Res;
+ private:
+ ControlData_t GO_M8010_6_motor_send_data;
+ MasterComdDataV3 A1B1_motor_send_data;
+};
+
+struct MotorData{
+ public:
+ MotorData(){}
+ MotorType motorType;
+ int hex_len;
+ unsigned char motor_id;
+ unsigned char mode;
+ int temp;
+ int merror;
+ float tau;
+ float dq;
+ float q;
+
+ bool correct = false;
+ bool extract_data(MotorData* motor_r);
+ uint8_t* get_motor_recv_data();
+
+ int footForce;
+ float LW;
+ int Acc;
+
+ float gyro[3];
+ float acc[3];
+ private:
+ MotorData_t GO_M8010_6_motor_recv_data;
+ ServoComdDataV3 A1B1_motor_recv_data;
+};
+
+// Utility Function
+int queryMotorMode(MotorType motortype,MotorMode motormode);
+float queryGearRatio(MotorType motortype);
+#endif // UNITREEMOTOR_H
\ No newline at end of file
diff --git a/src/unitree_motor/launch/unitree_motor.launch b/src/unitree_motor/launch/unitree_motor.launch
new file mode 100644
index 0000000..c2eee82
--- /dev/null
+++ b/src/unitree_motor/launch/unitree_motor.launch
@@ -0,0 +1,6 @@
+
+
+
+
+
+
\ No newline at end of file
diff --git a/src/unitree_motor/msg/MotorFeedback.msg b/src/unitree_motor/msg/MotorFeedback.msg
new file mode 100644
index 0000000..62b54ce
--- /dev/null
+++ b/src/unitree_motor/msg/MotorFeedback.msg
@@ -0,0 +1,6 @@
+int32 id
+float32 tau
+float32 pos
+float32 vel
+int32 temp
+int32 merror
\ No newline at end of file
diff --git a/src/unitree_motor/msg/MotorFeedbackArray.msg b/src/unitree_motor/msg/MotorFeedbackArray.msg
new file mode 100644
index 0000000..afdea52
--- /dev/null
+++ b/src/unitree_motor/msg/MotorFeedbackArray.msg
@@ -0,0 +1 @@
+unitree_motor/MotorFeedback[] motors
\ No newline at end of file
diff --git a/src/unitree_motor/package.xml b/src/unitree_motor/package.xml
new file mode 100644
index 0000000..2e91ad7
--- /dev/null
+++ b/src/unitree_motor/package.xml
@@ -0,0 +1,26 @@
+
+
+ unitree_motor
+ 0.0.0
+ The unitree_motor package
+
+ user
+
+ TODO
+
+ catkin
+
+ roscpp
+ rospy
+ std_msgs
+ message_generation
+
+ roscpp
+ rospy
+ std_msgs
+ message_runtime
+
+
+
+
+
\ No newline at end of file
diff --git a/src/unitree_motor/src/changeID.cpp b/src/unitree_motor/src/changeID.cpp
new file mode 100755
index 0000000..6292444
--- /dev/null
+++ b/src/unitree_motor/src/changeID.cpp
@@ -0,0 +1,52 @@
+#include
+#include
+#include
+#include
+#include "serialPort/SerialPort.h"
+#include "unitreeMotor/unitreeMotor.h"
+
+#define BroadAllMotorID 0xBB
+#define MotorPulsator 11
+
+int main(){
+ char serial_name[100];
+
+ MotorCmd motor_s;
+ MotorData motor_r;
+
+ motor_s.motorType = MotorType::B1; // set the motor type, A1 or B1
+ motor_r.motorType = motor_s.motorType;
+
+ printf("Please input the name of serial port.(e.g. Linux:/dev/ttyUSB0, Windows:\\\\.\\COM3)\n");
+ scanf("%s",serial_name);
+ printf("The serial port is %s\n", serial_name);
+
+ SerialPort serial(serial_name); // set the serial port name
+
+ motor_s.id = BroadAllMotorID;
+ motor_s.mode = 10;
+ serial.sendRecv(&motor_s, &motor_r);
+
+ usleep(100000); //sleep 0.1s
+
+ //进入拨轮模式(修改ID)
+ motor_s.mode = MotorPulsator;
+ motor_s.modify_data(&motor_s);
+ serial.send(motor_s.get_motor_send_data(), motor_s.hex_len);
+
+ printf("Please turn the motor.\n");
+ printf("One time: id=0; Two times: id=1, Three times: id=2\n");
+ printf("ID can only be 0, 1, 2\n");
+ printf("Once finished, press 'a'\n");
+
+ // int c;
+ while(getchar() != (int)'a');
+ printf("Turn finished\n");
+
+ //保存ID
+ motor_s.mode = 0;
+ motor_s.modify_data(&motor_s);
+ serial.send(motor_s.get_motor_send_data(), motor_s.hex_len);
+
+ return 0;
+}
diff --git a/src/unitree_motor/src/example_a1_motor.cpp b/src/unitree_motor/src/example_a1_motor.cpp
new file mode 100644
index 0000000..2637dad
--- /dev/null
+++ b/src/unitree_motor/src/example_a1_motor.cpp
@@ -0,0 +1,35 @@
+#include
+#include "serialPort/SerialPort.h"
+#include "unitreeMotor/unitreeMotor.h"
+
+
+int main() {
+
+ SerialPort serial("/dev/ttyUSB0");
+ MotorCmd cmd;
+ MotorData data;
+
+ while(true)
+ {
+ cmd.motorType = MotorType::A1;
+ data.motorType = MotorType::A1;
+ cmd.mode = queryMotorMode(MotorType::A1,MotorMode::FOC);
+ cmd.id = 0;
+ cmd.kp = 0.0;
+ cmd.kd = 2;
+ cmd.q = 0.0;
+ cmd.dq = -6.28*queryGearRatio(MotorType::A1);
+ cmd.tau = 0.0;
+ serial.sendRecv(&cmd,&data);
+
+ std::cout << std::endl;
+ std::cout << "motor.q: " << data.q << std::endl;
+ std::cout << "motor.temp: " << data.temp << std::endl;
+ std::cout << "motor.W: " << data.dq << std::endl;
+ std::cout << "motor.merror: " << data.merror << std::endl;
+ std::cout << std::endl;
+
+ usleep(200);
+ }
+
+}
\ No newline at end of file
diff --git a/src/unitree_motor/src/example_a1_motor_output.cpp b/src/unitree_motor/src/example_a1_motor_output.cpp
new file mode 100644
index 0000000..2f5b4b6
--- /dev/null
+++ b/src/unitree_motor/src/example_a1_motor_output.cpp
@@ -0,0 +1,65 @@
+#include
+#include "serialPort/SerialPort.h"
+#include "unitreeMotor/unitreeMotor.h"
+#include
+#define PI 3.1415926
+
+int main() {
+
+ SerialPort serial("/dev/ttyUSB0");
+ MotorCmd cmd;
+ MotorData data;
+
+ float output_kp = 25;
+ float output_kd = 0.6;
+ float rotor_kp = 0;
+ float rotor_kd = 0;
+ float gear_ratio = queryGearRatio(MotorType::A1);
+ float sin_counter = 0.0;
+
+ rotor_kp = (output_kp / (gear_ratio * gear_ratio)) / 26.07;
+ rotor_kd = (output_kd / (gear_ratio * gear_ratio)) * 100.0;
+
+ cmd.motorType = MotorType::A1;
+ data.motorType = MotorType::A1;
+ cmd.mode = queryMotorMode(MotorType::A1,MotorMode::FOC);
+ cmd.id = 0;
+ cmd.kp = 0.0;
+ cmd.kd = 0.0;
+ cmd.q = 0.0;
+ cmd.dq = 0.0;
+ cmd.tau = 0.0;
+ serial.sendRecv(&cmd,&data);
+ float output_angle_c;
+ output_angle_c = (data.q / gear_ratio) * (180/PI);
+ while(true)
+ {
+ sin_counter+=0.0001;
+ float output_angle_d;
+ output_angle_d = output_angle_c + 90 * sin(2*PI*sin_counter);
+ float rotor_angle_d = (output_angle_d * (PI/180)) * gear_ratio;
+ cmd.motorType = MotorType::A1;
+ data.motorType = MotorType::A1;
+ cmd.mode = queryMotorMode(MotorType::A1,MotorMode::FOC);
+ cmd.id = 0;
+ cmd.kp = rotor_kp;
+ cmd.kd = rotor_kd;
+ cmd.q = rotor_angle_d;
+ cmd.dq = 0.0;
+ cmd.tau = 0.0;
+ serial.sendRecv(&cmd,&data);
+
+
+ std::cout << std::endl;
+ std::cout << "motor.q: " << data.q / gear_ratio << std::endl;
+ std::cout << "motor.temp: " << data.temp << std::endl;
+ std::cout << "motor.W: " << data.dq / gear_ratio << std::endl;
+ std::cout << "motor.merror: " << data.merror << std::endl;
+ std::cout << "rotor_kp: " << rotor_kp << std::endl;
+ std::cout << "rotor_kd: " << rotor_kd << std::endl;
+ std::cout << std::endl;
+
+ usleep(200);
+ }
+
+}
\ No newline at end of file
diff --git a/src/unitree_motor/src/example_b1_motor.cpp b/src/unitree_motor/src/example_b1_motor.cpp
new file mode 100644
index 0000000..9697959
--- /dev/null
+++ b/src/unitree_motor/src/example_b1_motor.cpp
@@ -0,0 +1,35 @@
+#include
+#include "serialPort/SerialPort.h"
+#include "unitreeMotor/unitreeMotor.h"
+
+
+int main() {
+
+ SerialPort serial("/dev/ttyUSB0");
+ MotorCmd cmd;
+ MotorData data;
+
+ while(true)
+ {
+ cmd.motorType = MotorType::B1;
+ data.motorType = MotorType::B1;
+ cmd.mode = queryMotorMode(MotorType::B1,MotorMode::FOC);
+ cmd.id = 0;
+ cmd.kp = 0.0;
+ cmd.kd = 3;
+ cmd.q = 0.0;
+ cmd.dq = -6.28*queryGearRatio(MotorType::B1);
+ cmd.tau = 0.0;
+ serial.sendRecv(&cmd,&data);
+
+ std::cout << std::endl;
+ std::cout << "motor.q: " << data.q << std::endl;
+ std::cout << "motor.temp: " << data.temp << std::endl;
+ std::cout << "motor.W: " << data.dq << std::endl;
+ std::cout << "motor.merror: " << data.merror << std::endl;
+ std::cout << std::endl;
+
+ usleep(200);
+ }
+
+}
\ No newline at end of file
diff --git a/src/unitree_motor/src/example_goM8010_6_motor.cpp b/src/unitree_motor/src/example_goM8010_6_motor.cpp
new file mode 100644
index 0000000..d816123
--- /dev/null
+++ b/src/unitree_motor/src/example_goM8010_6_motor.cpp
@@ -0,0 +1,35 @@
+#include
+#include "serialPort/SerialPort.h"
+#include "unitreeMotor/unitreeMotor.h"
+
+
+int main() {
+
+ SerialPort serial("/dev/ttyUSB0");
+ MotorCmd cmd;
+ MotorData data;
+
+ while(true)
+ {
+ cmd.motorType = MotorType::GO_M8010_6;
+ data.motorType = MotorType::GO_M8010_6;
+ cmd.mode = queryMotorMode(MotorType::GO_M8010_6,MotorMode::FOC);
+ cmd.id = 0;
+ cmd.kp = 0.0;
+ cmd.kd = 0.01;
+ cmd.q = 0.0;
+ cmd.dq = -6.28*queryGearRatio(MotorType::GO_M8010_6);
+ cmd.tau = 0.0;
+ serial.sendRecv(&cmd,&data);
+
+ std::cout << std::endl;
+ std::cout << "motor.q: " << data.q << std::endl;
+ std::cout << "motor.temp: " << data.temp << std::endl;
+ std::cout << "motor.W: " << data.dq << std::endl;
+ std::cout << "motor.merror: " << data.merror << std::endl;
+ std::cout << std::endl;
+
+ usleep(200);
+ }
+
+}
\ No newline at end of file
diff --git a/src/unitree_motor/src/unitree_motor.cpp b/src/unitree_motor/src/unitree_motor.cpp
new file mode 100644
index 0000000..528f822
--- /dev/null
+++ b/src/unitree_motor/src/unitree_motor.cpp
@@ -0,0 +1,71 @@
+// filepath: /home/robofish/motor_control/src/unitree_motor/src/unitree_motor.cpp
+#include
+#include
+#include "serialPort/SerialPort.h"
+#include "unitreeMotor/unitreeMotor.h"
+#include "unitree_motor/MotorFeedback.h"
+#include "unitree_motor/MotorFeedbackArray.h"
+
+int main(int argc, char **argv) {
+ ros::init(argc, argv, "unitree_motor_node");
+ ros::NodeHandle nh;
+
+ std::string motor_type;
+ nh.param("motor_type", motor_type, "GO_M8010_6"); // default motor type
+
+ SerialPort serial("/dev/ttyACM0");
+ MotorCmd cmd;
+ MotorData data;
+
+ std::vector motor_ids = {0, 1}; // 定义电机ID列表
+
+ ros::Publisher motor_pub = nh.advertise("motor_feedback", 1000);
+
+ ros::Rate loop_rate(200); // 200 Hz
+
+ while (ros::ok()) {
+ unitree_motor::MotorFeedbackArray feedback_array;
+ for (int id : motor_ids) {
+ if (motor_type == "GO_M8010_6") {
+ cmd.motorType = MotorType::GO_M8010_6;
+ data.motorType = MotorType::GO_M8010_6;
+ cmd.mode = queryMotorMode(MotorType::GO_M8010_6, MotorMode::FOC);
+ }
+ // 你可以在这里添加其他电机类型的处理逻辑
+
+ cmd.id = id;
+ cmd.kp = 0.0;
+ cmd.kd = 0.0;
+ cmd.q = 0.0;
+ cmd.dq = 0.0;
+ cmd.tau = 0.0;
+ serial.sendRecv(&cmd, &data);
+
+ unitree_motor::MotorFeedback feedback;
+ feedback.id = id;
+ feedback.tau = data.tau;
+ feedback.pos = data.q;
+ feedback.vel = data.dq;
+ feedback.temp = data.temp;
+ feedback.merror = data.merror;
+
+ feedback_array.motors.push_back(feedback);
+
+ if (data.merror == 0) {
+ ROS_INFO("motor.id: %d", id);
+ ROS_INFO("motor.tau: %f", data.tau);
+ ROS_INFO("motor.pos: %f", data.q);
+ ROS_INFO("motor.vel: %f", data.dq);
+ } else {
+ ROS_WARN("motor id=%d does not reply", id);
+ }
+ }
+
+ motor_pub.publish(feedback_array);
+
+ ros::spinOnce();
+ loop_rate.sleep();
+ }
+
+ return 0;
+}
\ No newline at end of file