众擎机器人开源代码解读

发布于:2025-09-03 ⋅ 阅读:(16) ⋅ 点赞:(0)

一,综述

EngineAI ROS 包:

  • 高层开发模式:用户可通过发布身体速度指令,直接调用 EngineAI 机器人的行走控制器。
  • 底层开发模式:用户可通过发布关节指令,自主开发专属的控制器。
  • ROS2 package:全称为 “Robot Operating System 2 Package”(机器人操作系统 2 功能包),是 ROS2 生态中用于组织代码、配置文件等资源的基本单元,便于模块化开发与复用。
  • body velocity command:“身体速度指令”,通常包含机器人在三维空间中的线速度(如前后、左右移动速度)和角速度(如转向速度),是高层控制中常用的指令类型,无需用户关注单个关节的运动细节。
  • joint command:“关节指令”,针对机器人单个或多个关节的控制指令(如目标角度、角速度等),底层开发模式下用户需通过该指令精确控制关节运动,以实现自定义动作或控制逻辑。

二,接口协议

Topic/Service Name

Type

Rate Message Description DataStructure
/hardware/gamepad_keys Topic Publish >=500hz GamepadKeys.msg Gamepad Message Feedback

# Timestamp field using ROS2 header
uint8 LB = 0
uint8 RB = 1
uint8 A = 2
uint8 B = 3
uint8 X = 4
uint8 Y = 5
uint8 BACK = 6
uint8 START = 7
uint8 CROSS_X_UP = 8
uint8 CROSS_X_DOWN = 9
uint8 CROSS_Y_LEFT = 10
uint8 CROSS_Y_RIGHT = 11

uint8 LT = 0
uint8 RT = 1
uint8 LEFT_STICK_X = 2
uint8 LEFT_STICK_Y = 3
uint8 RIGHT_STICK_X = 4
uint8 RIGHT_STICK_Y = 5

std_msgs/Header header

# Digital buttons (0 = released, 1 = pressed)
int32[12] digital_states  # Fixed size array of 12 elements

# Analog inputs (range: -1.0 to 1.0)
float64[6] analog_states  # Fixed size array of 6 elements

/hardware/imu_info Topic Publish >=500hz IMUInfo.msg IMU Sensor Feedback std_msgs/Header header
geometry_msgs/Quaternion quaternion
geometry_msgs/Vector3 rpy
geometry_msgs/Vector3 linear_acceleration
geometry_msgs/Vector3 angular_velocity
 
/hardware/joint_state Topic Publish >=500hz JointState.msg Joint Status Feedback std_msgs/Header header
float64[] position
float64[] velocity
float64[] torque
 
/hardware/joint_command Topic Subscription 0~500hz JointCommand.msg Joint Command Subscription std_msgs/Header header
float64[] position
float64[] velocity
float64[] feed_forward_torque
float64[] torque
float64[] stiffness
float64[] damping
uint8 parallel_parser_type
/motion/motion_state Topic Publish >=5hz MotionState.msg Motion Status Feedback of Robot string current_motion_task
/hardware/motor_debug Topic Publish >=50hz MotorDebug.msg Feedback of Temperature, Tau, etc. float64[] tau_cmd
float64[] mos_temperature
float64[] motor_temperature
/motion/body_vel_cmd Topic Publish >=5hz BodyVelCmd.msg body velocity command publish, linear_x_vel ranges [-0.5m/s +0.5m/s] linear_y_vel ranges [-0.2m/s, +0.2m/s], yaw_vel rangs [-0.5rad/s, 0.5rad/s]

std_msgs/Header header


float64[] linear_velocity


float64 yaw_velocity

/heartbeat

std_msgs/Header header

string node_name

int64 startup_timestamp

# idle, running, error, sleep
string node_status

int64 error_code

string error_message

/enablemotor serve EnableMotor.srv bool enable
---
bool success
string message
 

三,工作区架构及编译环境

└── src
    ├── interface_example # Interface examples, recommended to run on Nezha
    ├── interface_protocol # Interface protocols, common modules
    ├── third_party # Third-party libraries
    ├── simulation # Simulation environment running on host
  • Ubuntu 22.04
  • ROS2 Humble Desktop
  • GCC >= 11
  • CMake >= 3.22
  • Python >= 3.10

四,FSM 三个模式:操纵杆模式,高层开发模式,底层开发模式

操纵杆模式、高层开发模式和底层开发模式的有限状态机(FSM)

操纵杆状态机

注意:LB+CORSS_Y_LEFT 是切入 joint commands即低层开发控制

高层开发模式

Body Velocity Control

底层开发模式

底层开发(Low-level Development)允许用户使用基于 EngineAI 开源强化学习(RL)训练框架(仓库地址:https://github.com/engineai-robotics/engineai_gym)训练的自定义强化学习控制器。用户可按照以下步骤逐步操作,实现基于 Mujoco 模拟器的 “仿真到仿真”(sim2sim)功能及实际部署。

五,部署操作:
在主机上运行 rl_basic_example 程序

步骤 1:进入 PD 站立模式(pd-stand mode)

  1. 确保机器人稳固放置在平整地面上,且周围有足够操作空间;
  2. 使用遥控器进入 PD 站立模式;
  3. 继续操作前,请确认机器人已稳定站立。

步骤 2:进入关节桥接模式(joint bridge mode)

关节桥接模式支持通过关节指令对机器人进行控制,操作步骤如下:

  1. 当机器人处于 PD 站立模式时,按下遥控器的【LB 键 + 左十字键 Y 向(CROSS_Y_LEFT)】组合键;
  2. 机器人将进入关节桥接模式,此时可通过关节指令对其进行控制;
  3. 执行以下命令验证机器人状态:

    bash

    # 在主机端执行
    ros2 topic echo /motion/motion_state
    
  4. 继续操作前,请确认运动状态(motion state)显示为 “joint_bridge”。

步骤 3:运行强化学习(RL)示例程序

安全警告(SAFETY WARNING)
  • 确保所有人员与机器人保持安全距离;
  • 若机器人出现异常动作,请随时准备紧急停止(可按下急停按钮或使机器人进入被动模式)。
启动示例程序 执行以下命令启动示例程序:bash
# 在主机端执行
ros2 launch interface_example rl_basic_example.launch.py

六,编译

几个脚本梳理:

1)同步代码到板级
主机(host) 端执行以下命令:./scripts/sync_src.sh nezha
(说明:“nezha” 指 “哪吒” 目标板,是该机器人系统适配的硬件设备;sync_src.sh为代码同步脚本,用于将主机端的开发代码传输到目标板,确保两端代码一致性。)
2)构建工作空间
        首先通过 SSH 连接到哪吒板(Nezha board),并进入工作空间目录:
cd ~/source/engineai_workspace
(说明:~/source/engineai_workspace是代码在目标板上的默认工作空间路径,cd命令用于切换到该目录。)
        然后执行构建脚本,编译节点代码:
./scripts/build_nodes.sh
(说明:build_nodes.sh是用于编译机器人功能节点的脚本,“nodes” 指 ROS 2 框架中的 “节点”,是实现具体功能的可执行单元,编译后生成可运行的程序文件。)
3)运行 PlotJuggler 进行数据监控
主机(host) 端编译interface_protocol功能包:
# in host
colcon build --packages-select interface_protocol
(说明:colcon是 ROS 2 的官方构建工具,--packages-select interface_protocol表示仅编译 “interface_protocol” 这一个功能包,该包通常包含机器人的数据通信协议相关代码。)
source install/setup.bash
(说明:source命令用于加载脚本文件,install/setup.bash是编译后生成的环境配置脚本,加载后主机才能识别并运行后续的 ROS 2 程序。)
ros2 run plotjuggler plotjuggler -n
(说明:ros2 run用于启动 ROS 2 功能包中的可执行程序,-n是 PlotJuggler 的参数,全称 “--no-config”,表示不自动加载之前保存的配置文件,便于用户重新选择需监控的数据话题。)
src/interface_protocol/pm_data_layout.xml
(说明:“layout file”(布局文件)包含数据图表的排列、待监控的话题选择等配置,加载后无需手动设置即可直接查看预设的机器人关键数据,如关节角度、电机电流等。)
 

check_format.sh

使用场景

这个脚本通常会集成到 CI/CD 流程中,在代码提交或 PR 创建时自动运行,确保提交的代码符合项目的格式规范。也可以在开发过程中手动运行,提前发现并修复格式问题。

依赖工具

脚本需要以下工具在系统中可用:

  • clang-format (用于 C/C++ 格式化)
  • yamllint (用于 YAML 文件检查)
  • autopep8 (用于 Python 格式检查)
  • git (用于检查文件变更)

如果需要修改检查规则,可以相应调整各工具的配置文件(如.clang-format、.yamllint 等)。

七,代码解析

interface_example

        --components

        message_handler.cc
 
一个 ROS 2 消息处理器类MessageHandler,负责订阅和发布各种 ROS 消息,是 ROS 2 节点与外部通信的关键组件

功能简述:MessageHandler类封装了 ROS 2 的订阅者 (subscriber) 和发布者 (publisher),用于处理与硬件和运动控制相关的消息,包括游戏手柄输入、IMU 传感器数据、关节状态和运动状态,并能发布关节控制命令

#include "message_handler.hpp"
#include <rclcpp/qos.hpp>

namespace example {

/* 
接收一个 ROS 2 节点的智能指针并存储,所有的 ROS 通信操作都依赖这个节点对象
这是 ROS 2 中常见的设计模式,将通信功能封装在独立类中,通过节点指针与 ROS 系统交互
*/
MessageHandler::MessageHandler(rclcpp::Node::SharedPtr node) : node_(node) {}

void MessageHandler::Initialize() {
  rclcpp::QoS qos(3);
  qos.best_effort();
  qos.durability_volatile();
/*
rclcpp::QoS qos(3):创建 QoS 配置,设置消息队列深度为 3
qos.best_effort():使用 "尽力而为" 策略,不保证消息可靠传递但开销小
qos.durability_volatile():非持久化,新订阅者不会收到历史消息
这种配置适合实时性要求高但对消息丢失不敏感的场景(如传感器数据)
*/
  // Initialize subscribers 初始化订阅
  // 游戏手柄消息订阅
  /*
    模板参数指定消息类型:interface_protocol::msg::GamepadKeys
    第一个参数是订阅的话题名:/hardware/gamepad_keys
    第二个参数是 QoS 配置
    第三个参数是回调函数绑定,当收到消息时调用GamepadCallback 会在回调函数再去做内部变量的传递
  */
  gamepad_sub_ = node_->create_subscription<interface_protocol::msg::GamepadKeys>(
      "/hardware/gamepad_keys", qos, 
    std::bind(&MessageHandler::GamepadCallback, this, std::placeholders::_1));

  imu_sub_ = node_->create_subscription<interface_protocol::msg::ImuInfo>(
      "/hardware/imu_info", qos, 
    std::bind(&MessageHandler::ImuCallback, this, std::placeholders::_1));

  joint_state_sub_ = node_->create_subscription<interface_protocol::msg::JointState>(
      "/hardware/joint_state", qos, 
    std::bind(&MessageHandler::JointStateCallback, this, std::placeholders::_1));


  // Initialize publisher 初始化发布
  //发布joint_command
  /*
    创建发布者,用于发布interface_protocol::msg::JointCommand类型消息
    发布到/hardware/joint_command话题,使用前面定义的 QoS 配置
  */

  joint_cmd_pub_ = node_->create_publisher<interface_protocol::msg::JointCommand>("/hardware/joint_command", qos);

  motion_state_sub_ = node_->create_subscription<interface_protocol::msg::MotionState>(
      "/motion/motion_state", 1, std::bind(&MessageHandler::MotionStateCallback, this, std::placeholders::_1));
}



void MessageHandler::MotionStateCallback(const interface_protocol::msg::MotionState::SharedPtr msg) {
  latest_motion_state_ = msg;
}

void MessageHandler::GamepadCallback(const interface_protocol::msg::GamepadKeys::SharedPtr msg) {
  latest_gamepad_ = msg;
}

void MessageHandler::ImuCallback(const interface_protocol::msg::ImuInfo::SharedPtr msg) { latest_imu_ = msg; }

void MessageHandler::JointStateCallback(const interface_protocol::msg::JointState::SharedPtr msg) {
  latest_joint_state_ = msg;
}

//PublishJointCommand 俩种重载形式:1接收智能指针  2接收对象索引
void MessageHandler::PublishJointCommand(const interface_protocol::msg::JointCommand::SharedPtr command) {
  joint_cmd_pub_->publish(*command);
}
void MessageHandler::PublishJointCommand(const interface_protocol::msg::JointCommand& command) {
  joint_cmd_pub_->publish(command);
}
}  // namespace example

        --src

       hold_joint_status.cc目的:可以熟悉下ROS2节点
                
        joint_test_example.cc
                
        rl_basic_example.cc
              

simulation
          


网站公告

今日签到

点亮在社区的每一天
去签到