全称:Multi-Joints Robot Simulator
代码地址:https://github.com/Jelatine/mj_robot_sim
设计目的
- 个人学习
opengl
的技术落地尝试 - 设计一个跨平台、轻量级的机器人仿真软件,方便调试机器人
特性
- 轻量级,接口简单易用
- 跨平台,可运行在
Windows
、Linux
环境 - 通过
glfw3
、glad
和glm
搭建opengl
三维显示窗口 - 使用URDF加载机器人数据,其中通过
urdfdom
库解析URDF文件,assimp
库导入模型文件 - 支持多窗口同时显示
依赖库
- glad
- glfw3
- glm
- assimp
- urdfdom
建议使用vcpkg安装
vcpkg install glad
vcpkg install glfw3
vcpkg install glm
vcpkg install assimp
vcpkg install urdfdom
编译
使用CMAKE_TOOLCHAIN_FILE
指定本机vcpkg.cmake
路径,以下/path
为示例
mkdir build
cd build
cmake .. -DCMAKE_TOOLCHAIN_FILE=/path/vcpkg/scripts/buildsystems/vcpkg.cmake
cmake --build .
接口
构造函数
/**
* 多关节机器人仿真软件接口
* @param _urdf URDF文件路径
*/
explicit MJRobotSim(const std::string &_urdf);
启动窗口界面
/**
* 启动仿真界面
* @return -1 模型加载失败, >=0 可动关节数量(REVOLUTE,CONTINUOUS,PRISMATIC)
*/
int start();
获取关节数量
/**
* 获取可动关节数量(REVOLUTE,CONTINUOUS,PRISMATIC)
* @return 关节数量
*/
unsigned int size() const;
通过关节索引获取/设置关节值
/**
* 获取/设置关节值,单位: 旋转关节-度(°);平移关节-米(m)
* @param index 关节索引
* @return 关节值的引用
*/
double &operator[](const unsigned int &index);
通过关节名称获取/设置关节值,假设urdf
关节定义为<joint name="joint_a1" type="revolute">
,通过sim["joint_a1"]=30;
设置
/**
* 获取/设置关节值,单位: 旋转关节-度(°);平移关节-米(m)
* @param name 关节名称
* @return
*/
double &operator[](const std::string &name);
退出状态查询
/**
* 退出状态
* @return 1 运行中, 0 正常退出, -1 模型加载失败, -2 窗口加载失败
*/
int exit_status() const;
例程
最简例程
#include "mj_robot_sim.h"
#include <thread>
int main() {
MJRobotSim sim("urdf/ur5.urdf");
sim.start();
while (sim.exit_status() > 0) {
for (unsigned int i = 0; i < sim.size(); ++i) { sim[i] += 0.1; } // 关节运动测试
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
}
多窗口
#include "mj_robot_sim.h"
#include <thread>
int main() {
MJRobotSim sim("urdf/ur5.urdf");
sim.start();
MJRobotSim urdf_tutoral("urdf_tutorial/urdf/07-physics.urdf");
urdf_tutoral.start();
MJRobotSim abb("abb/abb_irb2400_support/urdf/irb2400.urdf");
abb.start();
int running_count{0};
do {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
running_count = 0; // 从零开始计算运行窗口个数
for (unsigned int i = 0; i < sim.size(); ++i) { sim[i] += 0.1; }
running_count += (sim.exit_status() > 0) ? (1) : (0);
for (unsigned int i = 0; i < urdf_tutoral.size(); ++i) { urdf_tutoral[i] += 0.1; }
running_count += (urdf_tutoral.exit_status() > 0) ? (1) : (0);
for (unsigned int i = 0; i < abb.size(); ++i) { abb[i] += 0.1; }
running_count += (abb.exit_status() > 0) ? (1) : (0);
} while (running_count > 0);
}
仓库Demo的编译选项
可通过编译选项USE_URDF_TUTORIAL
,USE_ABB_IRB2400
,USE_KUKA_LBR_IIWA
测试example/mjr_sim_demo.cpp
的多窗口显示,如下图所示:
cmake .. -DUSE_URDF_TUTORIAL=ON -DUSE_ABB_IRB2400=ON -DUSE_KUKA_LBR_IIWA=ON
问题&解决
Ubuntu16.04
通过vcpkg
安装glfw3
时提示Build error
原因:需要其他依赖库[glfw3] Build error #30144
解决:sudo apt install libxinerama-dev libxcursor-dev xorg-dev libglu1-mesa-dev pkg-config
Ubuntu16.04
通过vcpkg
安装assimp
时提示‘abs’ was not declared in this scope
原因:assimp
库需要c++17
标准
解决:升级编译工具Ubuntu16.04
通过vcpkg
安装urdfdom
时提示urdfdom/tinyxml build failure
原因:curl版本太低或不支持ssl
解决:安装最新版本curl及openssl
最后
目前还未支持xacro
的解析,自定义urdf
文件可参考这里
如各位对opengl
感兴趣,推荐这个网站
希望能邀请大家共同参与和完善此开源软件