From b47354ad1fc3a0282b3d831f201c647e85790093 Mon Sep 17 00:00:00 2001 From: 637823209 Date: Wed, 28 Jan 2026 13:35:38 +0800 Subject: [PATCH 1/4] fix:fixed a bug in start_rl_controlo_real.sh --- deploy/deploy_assets/scripts/start_rl_control_real.sh | 4 ++-- deploy/legged_system/src/LeggedSystem.cpp | 9 +++++++-- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/deploy/deploy_assets/scripts/start_rl_control_real.sh b/deploy/deploy_assets/scripts/start_rl_control_real.sh index 307945e..036b19b 100755 --- a/deploy/deploy_assets/scripts/start_rl_control_real.sh +++ b/deploy/deploy_assets/scripts/start_rl_control_real.sh @@ -12,7 +12,7 @@ echo $SHELL_FOLDER pushd "$SHELL_FOLDER"/../../ || exit source setup.bash export LD_LIBRARY_PATH=./deploy_assets/thirdparty/onnxruntime-linux-x64-1.19.2/lib:$LD_LIBRARY_PATH - export PLUGIN_INSTALL_DIR="$PWD/legged_system/bin/iceoryx_chn_cfg.yaml" - export AIMRT_CFG_PATH="$PWD/legged_system/bin" + export PLUGIN_INSTALL_DIR="$PWD/legged_system/bin" + export AIMRT_CFG_PATH="$PWD/legged_system/bin/iceoryx_chn_cfg.yaml" ros2 launch rl_controllers rl_control_real.launch.py popd || exit diff --git a/deploy/legged_system/src/LeggedSystem.cpp b/deploy/legged_system/src/LeggedSystem.cpp index d7363b8..50a4c09 100644 --- a/deploy/legged_system/src/LeggedSystem.cpp +++ b/deploy/legged_system/src/LeggedSystem.cpp @@ -384,10 +384,15 @@ hardware_interface::CallbackReturn LeggedSystemHardware::on_activate( void LeggedSystemHardware::aimrtInit(){ // Initialize if (!std::filesystem::exists(options_.cfg_file_path)) { - RCLCPP_ERROR(rclcpp::get_logger("LeggedSystemHardware"), "Config file not found: %s", options_.cfg_file_path.c_str()); - exit(-1); + RCLCPP_ERROR(rclcpp::get_logger("LeggedSystemHardware"),"Config file path does not exist: %s",options_.cfg_file_path.c_str()); + std::exit(EXIT_FAILURE); } + if (!std::filesystem::is_regular_file(options_.cfg_file_path)) { + RCLCPP_ERROR(rclcpp::get_logger("LeggedSystemHardware"),"Config path exists but is not a regular file: %s",options_.cfg_file_path.c_str()); + std::exit(EXIT_FAILURE); + } + try { RCLCPP_INFO(rclcpp::get_logger("LeggedSystemHardware"), "Initializing AimRTCore, config file: %s", options_.cfg_file_path.c_str()); core_.Initialize(options_); From b7efb3029494242226e9a6c71b651b5364c48e7b Mon Sep 17 00:00:00 2001 From: 637823209 Date: Wed, 28 Jan 2026 13:40:50 +0800 Subject: [PATCH 2/4] fix:fix readme --- README.zh_CN.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.zh_CN.md b/README.zh_CN.md index b370276..e949992 100644 --- a/README.zh_CN.md +++ b/README.zh_CN.md @@ -277,7 +277,7 @@ joints: effort: 2356.2239000041304 ``` -注意以上都是各个电机的状态,对于串联关节来说,即为关节角度,而对于并联关节来说,其等效的串联关节状态还需要进行额外计算。以下图的脚踝并联机构为例,要想得到 J1,J2 轴的角度,即脚掌的 pitch 和 roll,一般运控训练都会对等效串联关节进行训练,强化学习模型输入输出的为串联关节的状态和控制命令,还需进行一次串并联解算,解算代码可以参考 https://github.com/HuNingHe/closed\_loop\_ankle(已被集成到部署框架内部)。 +注意以上都是各个电机的状态,对于串联关节来说,即为关节角度,而对于并联关节来说,其等效的串联关节状态还需要进行额外计算。以下图的脚踝并联机构为例,要想得到 J1,J2 轴的角度,即脚掌的 pitch 和 roll,一般运控训练都会对等效串联关节进行训练,强化学习模型输入输出的为串联关节的状态和控制命令,还需进行一次串并联解算,解算代码可以参考(已被集成到部署框架内部)。 https://github.com/HuNingHe/closed\_loop\_ankle ![](images/image.png) From 2220490b617d582307e38fcd6c114bbe6fccbf34 Mon Sep 17 00:00:00 2001 From: 637823209 Date: Wed, 28 Jan 2026 13:46:15 +0800 Subject: [PATCH 3/4] again --- README.zh_CN.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.zh_CN.md b/README.zh_CN.md index e949992..c758c61 100644 --- a/README.zh_CN.md +++ b/README.zh_CN.md @@ -277,7 +277,8 @@ joints: effort: 2356.2239000041304 ``` -注意以上都是各个电机的状态,对于串联关节来说,即为关节角度,而对于并联关节来说,其等效的串联关节状态还需要进行额外计算。以下图的脚踝并联机构为例,要想得到 J1,J2 轴的角度,即脚掌的 pitch 和 roll,一般运控训练都会对等效串联关节进行训练,强化学习模型输入输出的为串联关节的状态和控制命令,还需进行一次串并联解算,解算代码可以参考(已被集成到部署框架内部)。 https://github.com/HuNingHe/closed\_loop\_ankle +注意以上都是各个电机的状态,对于串联关节来说,即为关节角度,而对于并联关节来说,其等效的串联关节状态还需要进行额外计算。以下图的脚踝并联机构为例,要想得到 J1,J2 轴的角度,即脚掌的 pitch 和 roll,一般运控训练都会对等效串联关节进行训练,强化学习模型输入输出的为串联关节的状态和控制命令,还需进行一次串并联解算。 +解算代码可以参考(已被集成到部署框架内部): https://github.com/HuNingHe/closed_loop_ankle ![](images/image.png) From 7f4a4b928de10610aff44834f267a75d6f039016 Mon Sep 17 00:00:00 2001 From: 637823209 Date: Wed, 28 Jan 2026 13:47:42 +0800 Subject: [PATCH 4/4] again --- README.zh_CN.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.zh_CN.md b/README.zh_CN.md index c758c61..9aeeab3 100644 --- a/README.zh_CN.md +++ b/README.zh_CN.md @@ -278,6 +278,7 @@ joints: ``` 注意以上都是各个电机的状态,对于串联关节来说,即为关节角度,而对于并联关节来说,其等效的串联关节状态还需要进行额外计算。以下图的脚踝并联机构为例,要想得到 J1,J2 轴的角度,即脚掌的 pitch 和 roll,一般运控训练都会对等效串联关节进行训练,强化学习模型输入输出的为串联关节的状态和控制命令,还需进行一次串并联解算。 + 解算代码可以参考(已被集成到部署框架内部): https://github.com/HuNingHe/closed_loop_ankle ![](images/image.png)