Unitree MuJoCo 键盘替代手柄控制说明
本文档说明如何在没有 Xbox/Switch 游戏手柄的情况下,使用键盘替代手柄控制 Unitree MuJoCo 仿真器中的机器人。(Isaac Sim训练+测试 → sim2sim → mujoco测试)

一、修改的文件汇总
共修改了 4 个源码文件 + 1 个配置文件,没有新增文件。
1.1 simulate/src/physics_joystick.h
修改内容:
- 添加
#include <GLFW/glfw3.h> - 添加全局变量声明
extern GLFWwindow* g_sim_window; - 新增
KeyboardJoystick类 ,继承自unitree::common::UnitreeJoystick- 构造函数接收
GLFWwindow*窗口指针 update()方法使用glfwGetKey()轮询按键状态- 将键盘按键映射为手柄的按钮和摇杆轴
- 构造函数接收
1.2 simulate/src/unitree_sdk2_bridge.h
修改内容:
- 在
UnitreeSDK2BridgeBase构造函数中,当joystick_type == "keyboard"时:- 创建
KeyboardJoystick(g_sim_window)实例
- 创建
1.3 simulate/src/main.cc
修改内容:
- 添加全局变量
GLFWwindow* g_sim_window = nullptr; - 添加
static GLFWkeyfun s_mujoco_key_callback = nullptr; - 修改
user_key_cb:先调用 MuJoCo 原生回调,再执行自定义逻辑(弹性带控制、复位) - 在
main()中:- 设置
g_sim_window = sim->platform_ui->window_ - 使用链式回调:
s_mujoco_key_callback = glfwSetKeyCallback(g_sim_window, user_key_cb)
- 设置
1.4 simulate/mujoco/simulate/simulate.cc
修改内容:
- 在
UiEvent()函数的最开始 添加按键屏蔽,在调用mjui_event()之前拦截所有键盘手柄使用的按键:- WASD、QEFGCVZX(大小写)
- 数字键 1、2
- Space、方向键、Tab、Enter
- 这些按键直接
return,不进入 MuJoCo 的任何处理流程
1.5 simulate/config.yaml
修改内容:
yaml
use_joystick: 1
joystick_type: "keyboard"
二、键盘映射表
| 键盘按键 | 对应手柄功能 | 类型 |
|---|---|---|
| W / S | 左摇杆 Y 轴 (前进/后退) | 轴 |
| A / D | 左摇杆 X 轴 (左/右平移) | 轴 |
| ↑ / ↓ | 右摇杆 Y 轴 (俯仰) | 轴 |
| ← / → | 右摇杆 X 轴 (偏航) | 轴 |
| Q | LT 左扳机 | 轴 |
| E | RT 右扳机 | 轴 |
| Space | A 按钮 | 按钮 |
| Left Shift | B 按钮 | 按钮 |
| F | X 按钮 | 按钮 |
| G | Y 按钮 | 按钮 |
| C | LB 左肩键 | 按钮 |
| V | RB 右肩键 | 按钮 |
| Enter | Start 按钮 | 按钮 |
| Tab | Back/Select 按钮 | 按钮 |
| Z | LS (左摇杆按下) | 按钮 |
| X | RS (右摇杆按下) | 按钮 |
| 1 | F1 按钮 | 按钮 |
| 2 | F2 按钮 | 按钮 |
三、操作步骤
3.1 前提条件
确保已安装 Unitree SDK2、MuJoCo 以及所有依赖库(yaml-cpp、GLFW、Boost 等)。
3.2 修改配置文件
编辑 simulate/config.yaml:
yaml
use_joystick: 1
joystick_type: "keyboard"
3.3 编译
bash
cd simulate/build
cmake ..
make -j$(nproc)
3.4 启动仿真器
bash
./unitree_mujoco
3.5 启动控制器(在另一个终端)
bash
cd deploy/robots/go2/build
./go2_ctrl --network wlp132s0
3.6 键盘控制
- 点击 MuJoCo 窗口使其获得焦点(重要!)
- 按 Q + Space(对应 L2 + A)进入 FixStand 模式
- 按 Enter(对应 Start)开始控制机器人
- 使用 WASD 控制移动,方向键 控制转向
四、技术说明
4.1 为什么不用 glfwSetKeyCallback?
最初尝试使用 glfwSetKeyCallback 来捕获键盘事件,但发现这会覆盖 MuJoCo 内置的键盘回调,导致 MuJoCo 自身的快捷键(如 Space 暂停、方向键步进等)全部失效。
4.2 解决方案:glfwGetKey() 轮询
改用 glfwGetKey() 在 KeyboardJoystick::update() 中直接轮询按键状态。这是 GLFW 官方明确标注的线程安全函数 ,可以在物理线程中安全调用。同时通过链式回调保留 MuJoCo 原生键盘处理。
4.3 冲突快捷键的处理
MuJoCo 使用键盘快捷键进行多种操作:
Space:暂停/播放仿真方向键:步进/后退仿真帧Tab:切换 UI 面板WASD:UI 导航(在控件间移动焦点)
这些与键盘手柄映射冲突。解决方案是在 simulate.cc 的 UiEvent() 函数最开始 ,调用 mjui_event() 之前就拦截所有冲突按键,直接 return 跳过 MuJoCo 的所有处理流程。
五、恢复手柄控制
如需恢复使用物理手柄,只需修改 config.yaml:
yaml
use_joystick: 1
joystick_type: "xbox" # 或 "switch"
joystick_device: "/dev/input/js0"
如需完全禁用手柄:
yaml
use_joystick: 0
附录:修改文件源码
A.1 simulate/src/physics_joystick.h
cpp
#pragma once
#include <iostream>
#include <unitree/dds_wrapper/common/unitree_joystick.hpp>
#include "joystick/joystick.h"
#include <memory>
#include <GLFW/glfw3.h>
extern GLFWwindow* g_sim_window;
class XBoxJoystick : public unitree::common::UnitreeJoystick
{
public:
XBoxJoystick(std::string device, int bits = 15)
: unitree::common::UnitreeJoystick()
{
js_ = std::make_unique<Joystick>(device);
if(!js_->isFound()) {
std::cout << "Error: Joystick open failed." << std::endl;
exit(1);
}
max_value_ = 1 << (bits - 1);
}
void update() override
{
js_->getState();
back(js_->button_[6]);
start(js_->button_[7]);
LB(js_->button_[4]);
RB(js_->button_[5]);
A(js_->button_[0]);
B(js_->button_[1]);
X(js_->button_[2]);
Y(js_->button_[3]);
up(js_->axis_[7] < 0);
down(js_->axis_[7] > 0);
left(js_->axis_[6] < 0);
right(js_->axis_[6] > 0);
LT(js_->axis_[2] > 0);
RT(js_->axis_[5] > 0);
lx(double(js_->axis_[0]) / max_value_);
ly(-double(js_->axis_[1]) / max_value_);
rx(double(js_->axis_[3]) / max_value_);
ry(-double(js_->axis_[4]) / max_value_);
}
private:
std::unique_ptr<Joystick> js_;
int max_value_;
};
class KeyboardJoystick : public unitree::common::UnitreeJoystick
{
public:
KeyboardJoystick(GLFWwindow* window) : unitree::common::UnitreeJoystick(), window_(window) {}
void update() override
{
if (!window_) return;
float lx_val = 0.0f, ly_val = 0.0f, rx_val = 0.0f, ry_val = 0.0f;
if (glfwGetKey(window_, GLFW_KEY_W) == GLFW_PRESS) ly_val += 1.0f;
if (glfwGetKey(window_, GLFW_KEY_S) == GLFW_PRESS) ly_val -= 1.0f;
if (glfwGetKey(window_, GLFW_KEY_A) == GLFW_PRESS) lx_val -= 1.0f;
if (glfwGetKey(window_, GLFW_KEY_D) == GLFW_PRESS) lx_val += 1.0f;
if (glfwGetKey(window_, GLFW_KEY_UP) == GLFW_PRESS) ry_val += 1.0f;
if (glfwGetKey(window_, GLFW_KEY_DOWN) == GLFW_PRESS) ry_val -= 1.0f;
if (glfwGetKey(window_, GLFW_KEY_LEFT) == GLFW_PRESS) rx_val -= 1.0f;
if (glfwGetKey(window_, GLFW_KEY_RIGHT) == GLFW_PRESS) rx_val += 1.0f;
float lt_val = (glfwGetKey(window_, GLFW_KEY_Q) == GLFW_PRESS) ? 1.0f : 0.0f;
float rt_val = (glfwGetKey(window_, GLFW_KEY_E) == GLFW_PRESS) ? 1.0f : 0.0f;
lx(lx_val);
ly(ly_val);
rx(rx_val);
ry(ry_val);
LT(lt_val);
RT(rt_val);
A((glfwGetKey(window_, GLFW_KEY_SPACE) == GLFW_PRESS) ? 1 : 0);
B((glfwGetKey(window_, GLFW_KEY_LEFT_SHIFT) == GLFW_PRESS) ? 1 : 0);
X((glfwGetKey(window_, GLFW_KEY_F) == GLFW_PRESS) ? 1 : 0);
Y((glfwGetKey(window_, GLFW_KEY_G) == GLFW_PRESS) ? 1 : 0);
LB((glfwGetKey(window_, GLFW_KEY_C) == GLFW_PRESS) ? 1 : 0);
RB((glfwGetKey(window_, GLFW_KEY_V) == GLFW_PRESS) ? 1 : 0);
start((glfwGetKey(window_, GLFW_KEY_ENTER) == GLFW_PRESS) ? 1 : 0);
back((glfwGetKey(window_, GLFW_KEY_TAB) == GLFW_PRESS) ? 1 : 0);
LS((glfwGetKey(window_, GLFW_KEY_Z) == GLFW_PRESS) ? 1 : 0);
RS((glfwGetKey(window_, GLFW_KEY_X) == GLFW_PRESS) ? 1 : 0);
F1((glfwGetKey(window_, GLFW_KEY_1) == GLFW_PRESS) ? 1 : 0);
F2((glfwGetKey(window_, GLFW_KEY_2) == GLFW_PRESS) ? 1 : 0);
up((glfwGetKey(window_, GLFW_KEY_UP) == GLFW_PRESS) ? 1 : 0);
down((glfwGetKey(window_, GLFW_KEY_DOWN) == GLFW_PRESS) ? 1 : 0);
left((glfwGetKey(window_, GLFW_KEY_LEFT) == GLFW_PRESS) ? 1 : 0);
right((glfwGetKey(window_, GLFW_KEY_RIGHT) == GLFW_PRESS) ? 1 : 0);
}
private:
GLFWwindow* window_;
};
class SwitchJoystick : public unitree::common::UnitreeJoystick
{
public:
SwitchJoystick(std::string device, int bits = 15)
: unitree::common::UnitreeJoystick()
{
js_ = std::make_unique<Joystick>(device);
if(!js_->isFound()) {
std::cout << "Error: Joystick open failed." << std::endl;
exit(1);
}
max_value_ = 1 << (bits - 1);
}
void update() override
{
js_->getState();
back(js_->button_[10]);
start(js_->button_[11]);
LB(js_->button_[6]);
RB(js_->button_[7]);
A(js_->button_[0]);
B(js_->button_[1]);
X(js_->button_[3]);
Y(js_->button_[4]);
up(js_->axis_[7] < 0);
down(js_->axis_[7] > 0);
left(js_->axis_[6] < 0);
right(js_->axis_[6] > 0);
LT(js_->axis_[5] > 0);
RT(js_->axis_[4] > 0);
lx(double(js_->axis_[0]) / max_value_);
ly(-double(js_->axis_[1]) / max_value_);
rx(double(js_->axis_[2]) / max_value_);
ry(-double(js_->axis_[3]) / max_value_);
}
private:
std::unique_ptr<Joystick> js_;
int max_value_;
};
A.2 simulate/src/unitree_sdk2_bridge.h
cpp
#pragma once
#include <mujoco/mujoco.h>
#include <unitree/robot/channel/channel_publisher.hpp>
#include <unitree/robot/channel/channel_subscriber.hpp>
#include <unitree/dds_wrapper/robots/go2/go2.h>
#include <unitree/dds_wrapper/robots/g1/g1.h>
#include <unitree/idl/hg/BmsState_.hpp>
#include <unitree/idl/hg/IMUState_.hpp>
#include <iostream>
#include "param.h"
#include "physics_joystick.h"
#define MOTOR_SENSOR_NUM 3
class UnitreeSDK2BridgeBase
{
public:
UnitreeSDK2BridgeBase(mjModel *model, mjData *data)
: mj_model_(model), mj_data_(data)
{
_check_sensor();
if(param::config.print_scene_information == 1) {
printSceneInformation();
}
if(param::config.use_joystick == 1) {
if(param::config.joystick_type == "xbox") {
joystick = std::make_shared<XBoxJoystick>(param::config.joystick_device, param::config.joystick_bits);
} else if(param::config.joystick_type == "switch") {
joystick = std::make_shared<SwitchJoystick>(param::config.joystick_device, param::config.joystick_bits);
} else if(param::config.joystick_type == "keyboard") {
joystick = std::make_shared<KeyboardJoystick>(g_sim_window);
} else {
std::cerr << "Unsupported joystick type: " << param::config.joystick_type << std::endl;
exit(EXIT_FAILURE);
}
}
}
// ... (其余代码不变)
A.3 simulate/src/main.cc(关键修改部分)
cpp
// 文件开头添加
#include <mujoco/mujoco.h>
#include "simulate.h"
#include "array_safety.h"
#include "unitree_sdk2_bridge.h"
#include "param.h"
GLFWwindow* g_sim_window = nullptr;
// user keyboard callback(链式回调,保留 MuJoCo 原生处理)
static GLFWkeyfun s_mujoco_key_callback = nullptr;
void user_key_cb(GLFWwindow* window, int key, int scancode, int act, int mods) {
if (s_mujoco_key_callback) {
s_mujoco_key_callback(window, key, scancode, act, mods);
}
if (act==GLFW_PRESS)
{
if(param::config.enable_elastic_band == 1) {
if (key==GLFW_KEY_9) {
elastic_band.enable_ = !elastic_band.enable_;
} else if (key==GLFW_KEY_7 || key==GLFW_KEY_UP) {
elastic_band.length_ -= 0.1;
} else if (key==GLFW_KEY_8 || key==GLFW_KEY_DOWN) {
elastic_band.length_ += 0.1;
}
}
if(key==GLFW_KEY_BACKSPACE) {
mj_resetData(m, d);
mj_forward(m, d);
}
}
}
// main() 函数中
int main(int argc, char **argv)
{
// ... (前面代码不变) ...
auto sim = std::make_unique<mj::Simulate>(
std::make_unique<mj::GlfwAdapter>(),
&cam, &opt, &pert, /* is_passive = */ false);
g_sim_window = static_cast<mj::GlfwAdapter*>(sim->platform_ui.get())->window_;
std::thread unitree_thread(UnitreeSdk2BridgeThread, nullptr);
std::thread physicsthreadhandle(&PhysicsThread, sim.get(), param::config.robot_scene.c_str());
// 链式回调,保留 MuJoCo 原生键盘处理
s_mujoco_key_callback = glfwSetKeyCallback(g_sim_window, user_key_cb);
sim->RenderLoop();
physicsthreadhandle.join();
return 0;
}
A.4 simulate/mujoco/simulate/simulate.cc(UiEvent 函数开头修改)
cpp
void UiEvent(mjuiState* state) {
mj::Simulate* sim = static_cast<mj::Simulate*>(state->userdata);
// Suppress keys used by keyboard joystick before UI processing
if (state->type==mjEVENT_KEY && state->key!=0) {
switch (state->key) {
case ' ':
case 'w':
case 'W':
case 'a':
case 'A':
case 's':
case 'S':
case 'd':
case 'D':
case 'q':
case 'Q':
case 'e':
case 'E':
case 'f':
case 'F':
case 'g':
case 'G':
case 'c':
case 'C':
case 'v':
case 'V':
case 'z':
case 'Z':
case 'x':
case 'X':
case '1':
case '2':
case mjKEY_RIGHT:
case mjKEY_LEFT:
case mjKEY_UP:
case mjKEY_DOWN:
case mjKEY_TAB:
case mjKEY_ENTER:
return;
}
}
// call UI 0 if event is directed to it
if ((state->dragrect==sim->ui0.rectid) ||
(state->dragrect==0 && state->mouserect==sim->ui0.rectid) ||
state->type==mjEVENT_KEY) {
// process UI event
mjuiItem* it = mjui_event(&sim->ui0, state, &sim->platform_ui->mjr_context());
// ... (后续代码不变) ...
A.5 simulate/config.yaml
yaml
robot: "go2"
robot_scene: "scene.xml"
domain_id: 0
interface: "wlp132s0"
use_joystick: 1
joystick_type: "keyboard"
joystick_device: "/dev/input/js0"
joystick_bits: 16
print_scene_information: 1
enable_elastic_band: 0