视频教程:
https://www.bilibili.com/video/BV1e44y1H7Mn/
资源请到tiny.cc/mujoco下载
涉及内容
本次课程制作了一个简单的小球模型,然后对小球进行简单的模拟,并演示了一些参数的作用。
小球模型:
<mujoco>
<worldbody>
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<geom type="plane" size="10 1 0.1" rgba=".9 0 0 1"/>
<body pos="0 0 1">
<joint type="free"/>
<geom type="sphere" size=".1" rgba="0 .9 0 1"/>
</body>
</worldbody>
</mujoco>
然后通过c代码来演示相机的一些设置,小球位置和速度的设置,给小球施drag force等,c代码如下:
#include<stdbool.h>
#include<math.h>
#include "mujoco.h"
#include "glfw3.h"
#include "stdio.h"
#include "stdlib.h"
#include "string.h"
char filename[] = "../myproject/projectile/ball.xml";
mjModel* m = NULL;
mjData* d = NULL;
mjvCamera cam;
mjvOption opt;
mjvScene scn;
mjrContext con;
bool button_left = false;
bool button_middle = false;
bool button_right = false;
double lastx = 0;
double lasty = 0;
mjtNum position_history = 0;
mjtNum previous_time = 0;
float_t ctrl_update_freq = 100;
mjtNum last_update = 0.0;
mjtNum ctrl;
void keyboard(GLFWwindow* window, int key, int scancode, int act, int mods)
{
if( act==GLFW_PRESS && key==GLFW_KEY_BACKSPACE )
{
mj_resetData(m, d);
mj_forward(m, d);
}
}
void mouse_button(GLFWwindow* window, int button, int act, int mods)
{
button_left = (glfwGetMouseButton(window, GLFW_MOUSE_BUTTON_LEFT)==GLFW_PRESS);
button_middle = (glfwGetMouseButton(window, GLFW_MOUSE_BUTTON_MIDDLE)==GLFW_PRESS);
button_right = (glfwGetMouseButton(window, GLFW_MOUSE_BUTTON_RIGHT)==GLFW_PRESS);
glfwGetCursorPos(window, &lastx, &lasty);
}
void mouse_move(GLFWwindow* window, double xpos, double ypos)
{
if( !button_left && !button_middle && !button_right )
return;
double dx = xpos - lastx;
double dy = ypos - lasty;
lastx = xpos;
lasty = ypos;
int width, height;
glfwGetWindowSize(window, &width, &height);
bool mod_shift = (glfwGetKey(window, GLFW_KEY_LEFT_SHIFT)==GLFW_PRESS ||
glfwGetKey(window, GLFW_KEY_RIGHT_SHIFT)==GLFW_PRESS);
mjtMouse action;
if( button_right )
action = mod_shift ? mjMOUSE_MOVE_H : mjMOUSE_MOVE_V;
else if( button_left )
action = mod_shift ? mjMOUSE_ROTATE_H : mjMOUSE_ROTATE_V;
else
action = mjMOUSE_ZOOM;
mjv_moveCamera(m, action, dx/height, dy/height, &scn, &cam);
}
void scroll(GLFWwindow* window, double xoffset, double yoffset)
{
mjv_moveCamera(m, mjMOUSE_ZOOM, 0, -0.05*yoffset, &scn, &cam);
}
int main(int argc, const char** argv)
{
mj_activate("mjkey.txt");
char error[1000] = "Could not load binary model";
if( argc<2 )
m = mj_loadXML(filename, 0, error, 1000);
else
if( strlen(argv[1])>4 && !strcmp(argv[1]+strlen(argv[1])-4, ".mjb") )
m = mj_loadModel(argv[1], 0);
else
m = mj_loadXML(argv[1], 0, error, 1000);
if( !m )
mju_error_s("Load model error: %s", error);
d = mj_makeData(m);
if( !glfwInit() )
mju_error("Could not initialize GLFW");
GLFWwindow* window = glfwCreateWindow(1244, 700, "Demo", NULL, NULL);
glfwMakeContextCurrent(window);
glfwSwapInterval(1);
mjv_defaultCamera(&cam);
mjv_defaultOption(&opt);
mjv_defaultScene(&scn);
mjr_defaultContext(&con);
mjv_makeScene(m, &scn, 2000);
mjr_makeContext(m, &con, mjFONTSCALE_150);
glfwSetKeyCallback(window, keyboard);
glfwSetCursorPosCallback(window, mouse_move);
glfwSetMouseButtonCallback(window, mouse_button);
glfwSetScrollCallback(window, scroll);
double arr_view[] = {90,-45, 4, 0.000000, 0.000000, 0.000000};
cam.azimuth = arr_view[0];
cam.elevation = arr_view[1];
cam.distance = arr_view[2];
cam.lookat[0] = arr_view[3];
cam.lookat[1] = arr_view[4];
cam.lookat[2] = arr_view[5];
d->qpos[2]=0.1;
d->qvel[2]=5;
d->qvel[0]=2;
while( !glfwWindowShouldClose(window))
{
mjtNum simstart = d->time;
while( d->time - simstart < 1.0/60.0 )
{
mj_step(m, d);
double vx, vy, vz;
vx = d->qvel[0]; vy = d->qvel[1]; vz = d->qvel[2];
double v;
v = sqrt(vx*vx+vy*vy+vz*vz);
double fx, fy, fz;
double c = 1;
fx = -c*v*vx;
fy = -c*v*vy;
fz = -c*v*vz;
d->qfrc_applied[0]=fx;
d->qfrc_applied[1]=fy;
d->qfrc_applied[2]=fz;
}
mjrRect viewport = {0, 0, 0, 0};
glfwGetFramebufferSize(window, &viewport.width, &viewport.height);
opt.frame = mjFRAME_WORLD;
cam.lookat[0] = d->qpos[0];
mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
mjr_render(viewport, &scn, &con);
glfwSwapBuffers(window);
glfwPollEvents();
}
mjv_freeScene(&scn);
mjr_freeContext(&con);
mj_deleteData(d);
mj_deleteModel(m);
mj_deactivate();
#if defined(__APPLE__) || defined(_WIN32)
glfwTerminate();
#endif
return 1;
}
窗口的键盘和鼠标事件绑定:
void keyboard(GLFWwindow* window, int key, int scancode, int act, int mods)
{
if( act==GLFW_PRESS && key==GLFW_KEY_BACKSPACE )
{
mj_resetData(m, d);
mj_forward(m, d);
}
}
void mouse_button(GLFWwindow* window, int button, int act, int mods)
{
button_left = (glfwGetMouseButton(window, GLFW_MOUSE_BUTTON_LEFT)==GLFW_PRESS);
button_middle = (glfwGetMouseButton(window, GLFW_MOUSE_BUTTON_MIDDLE)==GLFW_PRESS);
button_right = (glfwGetMouseButton(window, GLFW_MOUSE_BUTTON_RIGHT)==GLFW_PRESS);
glfwGetCursorPos(window, &lastx, &lasty);
}
void mouse_move(GLFWwindow* window, double xpos, double ypos)
{
if( !button_left && !button_middle && !button_right )
return;
double dx = xpos - lastx;
double dy = ypos - lasty;
lastx = xpos;
lasty = ypos;
int width, height;
glfwGetWindowSize(window, &width, &height);
bool mod_shift = (glfwGetKey(window, GLFW_KEY_LEFT_SHIFT)==GLFW_PRESS ||
glfwGetKey(window, GLFW_KEY_RIGHT_SHIFT)==GLFW_PRESS);
mjtMouse action;
if( button_right )
action = mod_shift ? mjMOUSE_MOVE_H : mjMOUSE_MOVE_V;
else if( button_left )
action = mod_shift ? mjMOUSE_ROTATE_H : mjMOUSE_ROTATE_V;
else
action = mjMOUSE_ZOOM;
mjv_moveCamera(m, action, dx/height, dy/height, &scn, &cam);
}
void scroll(GLFWwindow* window, double xoffset, double yoffset)
{
mjv_moveCamera(m, mjMOUSE_ZOOM, 0, -0.05*yoffset, &scn, &cam);
}
c中怎么加载xml模型
char error[1000] = "Could not load binary model";
if( argc<2 )
m = mj_loadXML(filename, 0, error, 1000);
else
if( strlen(argv[1])>4 && !strcmp(argv[1]+strlen(argv[1])-4, ".mjb") )
m = mj_loadModel(argv[1], 0);
else
m = mj_loadXML(argv[1], 0, error, 1000);
if( !m )
mju_error_s("Load model error: %s", error);
d = mj_makeData(m);
相机视角的旋转和聚焦点:azimuth 是旋转参数,lookat是聚焦点
double arr_view[] = {90,-45, 4, 0.000000, 0.000000, 0.000000};
cam.azimuth = arr_view[0];
cam.elevation = arr_view[1];
cam.distance = arr_view[2];
cam.lookat[0] = arr_view[3];
cam.lookat[1] = arr_view[4];
cam.lookat[2] = arr_view[5];
如果我们要相机追踪小球,可以像下面那样子做:
cam.lookat[1] =d->qpos[1];
设置小球的位置和速度
xml里面也可以设置,如果代码再设置,会覆盖掉xml的配置
d->qpos[2]=0.1;
d->qvel[2]=5;
d->qvel[0]=2;
给小球施加drag force mjData.qfrc_applied是基于关节局部坐标系来描述的
double vx, vy, vz;
vx = d->qvel[0]; vy = d->qvel[1]; vz = d->qvel[2];
double v;
v = sqrt(vx*vx+vy*vy+vz*vz);
double fx, fy, fz;
double c = 1;
fx = -c*v*vx;
fy = -c*v*vy;
fz = -c*v*vz;
d->qfrc_applied[0]=fx;
d->qfrc_applied[1]=fy;
d->qfrc_applied[2]=fz;
一些代码问题的记录
将mujoco的include 复制到parojectile上一级目录 parojecti le上一级目录中创建bin目录,然后将mujoco的lib文件复制到bin里
https://pan.baidu.com/s/1TalZP3sc-_is7nM26ozsSQ 提取码: jr76 从上面的链接中下载额外的h文件和so,分别放到include,bin下面
sudo apt install libglew-dev
到bin目录下:sudo ln -s libglew.so libGLEW.so.2.2,解决while loading shared libraries:libglew.so.2.2的问题
修改parojectile的makefile如下:
#MAC
#COMMON=-O2 -I../../include -L../../bin -mavx -pthread
#LIBS = -w -lmujoco200 -lglfw.3
#CC = gcc
#LINUX
COMMON=-O2 -I../include -L../bin -mavx -pthread -Wl,-rpath,'$$ORIGIN'
LIBS = ../bin/libmujoco.so -lGL -lm ../bin/libglew.so ../bin/libglfw.so.3
CC = gcc
#WINDOWS
#COMMON=/O2 /MT /EHsc /arch:AVX /I../../include /Fe../../bin/
#LIBS = ../../bin/glfw3.lib ../../bin/mujoco200.lib
#CC = cl
ROOT = projectile
all:
$(CC) $(COMMON) main.c $(LIBS) -o ../bin/$(ROOT)
main.o:
$(CC) $(COMMON) -c main.c
clean:
rm *.o ../bin/$(ROOT)
|