Mujoco 2D hopper

MuJoCo Lec9


在这里插入图片描述


在这里插入图片描述


hopper的状态机控制

pos servo,vel servo 组合的作用

  1. pos的增益有,vel的增益为0时,pos servo表现为在目标位置来回运动,好像弹簧的效果一样

Mujoco的auctor在目标位置震荡的演示

  1. pos的增益和vel的增益都有,就是PD控制,从而快速的到达目标位置并停下来

  //all actions
  if (fsm == fsm_air1)
  {
  	//落下状态,这里pos servo,vel servo的设置是为了让pos servo迅速停停下来
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,100);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,10);

    //d->ctrl[0] = 0;
  }

  if (fsm == fsm_stance1)
  {
      //if (fsm==fsm_air1 && z_foot < 0.05 )
	  //{
	    //fsm = fsm_stance1;
	    //printf("fsm_stance1 \n");
	  //}

   //vel的参数设0,同时增大pos servo的参数,这样auctor会在目标点附近来回摆动
   //从而产生抗压缩的作用
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,1000);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,0);
  }

  if (fsm == fsm_stance2)
  {
      //if (fsm== fsm_stance1 && vz_torso > 0)
	  //{
	    //fsm = fsm_stance2;
	    //printf("fsm_stance2 \n");
	  //}

    //这里如果跟stance1一样的话,系统的能量会衰减比较厉害,大概30步会停下来
    //增大一点,相当于给系统注入多一点能量,不要那么快停下来
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,1050);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,0);

    这里是顺时针旋转,这样子整个hopper是往前倾,从而底部的auctor产生
    //产生的力变为斜向上,以达到向前的目的
    d->ctrl[0] = -0.2;
  }

  if (fsm == fsm_air2)
  {
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,100);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,10);

    d->ctrl[0] = 0;//将脚的姿态恢复成垂直
  }


模型xml

<mujoco>

 <visual>
<headlight ambient="0.5 0.5 0.5"/>
 </visual>
	<option timestep="0.001" integrator="RK4" gravity="0 0 -9.81">
		<flag sensornoise="disable" contact="enable" energy="enable"/>
	</option>

	<worldbody>
    <!-- <light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/> -->
		<!-- <light mode="targetbody" target="torso" /> -->
		<geom type="plane" size="100 1 0.1" rgba=".9 0 0 1"/>
		<body name="torso" pos="0 0 2">
			<joint name="x" type="slide" pos="0 0 0" axis="1 0 0" />
			<joint name="z" type="slide" pos="0 0 0" axis="0 0 1" />
			<geom type="sphere" size="0.1" rgba=".9 .9 .9 1" mass="1"/>
			<body name="leg" pos="0 0 -0.5" euler="0 0 0">
				<joint name="hip" type="hinge" pos="0 0 0.5" axis="0 -1 0" />
				<geom type="cylinder" size=".05 .5" rgba="0 .9 0 1" mass="1"/>
				<body name="foot" pos="0 0 -0.75">
					<joint name="knee" type="slide" pos="0 0 0.25" axis="0 0 -1" />
					<geom type="cylinder" pos="0 0 0.125" size=".01 .125" rgba="0 0 .9 1" mass="0"/>
					<geom type="sphere" size="0.05" rgba=".9 .9 0 1" mass="0.1"/>
				</body>
			</body>
		</body>
	</worldbody>

	<actuator>
		<position name="pservo-hip" joint="hip" kp="0"/>
		<velocity name="vservo-hip" joint="hip" kv="0"/>
		<position name="pservo-knee" joint="knee" kp="0"/>
		<velocity name="vservo-knee" joint="knee" kv="0"/>
	</actuator>


</mujoco>

控制代码



#include<stdbool.h> //for bool
//#include<unistd.h> //for usleep
//#include <math.h>

#include "mujoco.h"
#include "glfw3.h"
#include "stdio.h"
#include "stdlib.h"
#include "string.h"

//simulation end time
double simend = 50;

int fsm;
#define fsm_air1 0
#define fsm_stance1 1
#define fsm_stance2 2
#define fsm_air2 3

int step_no;

//related to writing data to a file
FILE *fid;
int loop_index = 0;
const int data_frequency = 10; //frequency at which data is written to a file


// char xmlpath[] = "../myproject/template_writeData/pendulum.xml";
// char datapath[] = "../myproject/template_writeData/data.csv";


//Change the path <template_writeData>
//Change the xml file
char path[] = "../myproject/hopper/";
char xmlfile[] = "hopper.xml";


char datafile[] = "data.csv";


// MuJoCo data structures
mjModel* m = NULL;                  // MuJoCo model
mjData* d = NULL;                   // MuJoCo data
mjvCamera cam;                      // abstract camera
mjvOption opt;                      // visualization options
mjvScene scn;                       // abstract scene
mjrContext con;                     // custom GPU context

// mouse interaction
bool button_left = false;
bool button_middle = false;
bool button_right =  false;
double lastx = 0;
double lasty = 0;

// holders of one step history of time and position to calculate dertivatives
mjtNum position_history = 0;
mjtNum previous_time = 0;

// controller related variables
float_t ctrl_update_freq = 100;
mjtNum last_update = 0.0;
mjtNum ctrl;

// keyboard callback
void keyboard(GLFWwindow* window, int key, int scancode, int act, int mods)
{
    // backspace: reset simulation
    if( act==GLFW_PRESS && key==GLFW_KEY_BACKSPACE )
    {
        mj_resetData(m, d);
        mj_forward(m, d);
    }
}

// mouse button callback
void mouse_button(GLFWwindow* window, int button, int act, int mods)
{
    // update button state
    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);

    // update mouse position
    glfwGetCursorPos(window, &lastx, &lasty);
}


// mouse move callback
void mouse_move(GLFWwindow* window, double xpos, double ypos)
{
    // no buttons down: nothing to do
    if( !button_left && !button_middle && !button_right )
        return;

    // compute mouse displacement, save
    double dx = xpos - lastx;
    double dy = ypos - lasty;
    lastx = xpos;
    lasty = ypos;

    // get current window size
    int width, height;
    glfwGetWindowSize(window, &width, &height);

    // get shift key state
    bool mod_shift = (glfwGetKey(window, GLFW_KEY_LEFT_SHIFT)==GLFW_PRESS ||
                      glfwGetKey(window, GLFW_KEY_RIGHT_SHIFT)==GLFW_PRESS);

    // determine action based on mouse button
    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;

    // move camera
    mjv_moveCamera(m, action, dx/height, dy/height, &scn, &cam);
}


// scroll callback
void scroll(GLFWwindow* window, double xoffset, double yoffset)
{
    // emulate vertical mouse motion = 5% of window height
    mjv_moveCamera(m, mjMOUSE_ZOOM, 0, -0.05*yoffset, &scn, &cam);
}


//****************************
//This function is called once and is used to get the headers
void init_save_data()
{
  //write name of the variable here (header)
   fprintf(fid,"t, ");

   //Don't remove the newline
   fprintf(fid,"\n");
}

//***************************
//This function is called at a set frequency, put data here
void save_data(const mjModel* m, mjData* d)
{
  //data here should correspond to headers in init_save_data()
  //seperate data by a space %f followed by space
  fprintf(fid,"%f ",d->time);

  //Don't remove the newline
  fprintf(fid,"\n");
}

/******************************/
void set_torque_control(const mjModel* m,int actuator_no,int flag)
{
  if (flag==0)
    m->actuator_gainprm[10*actuator_no+0]=0;
  else
    m->actuator_gainprm[10*actuator_no+0]=1;
}
/******************************/


/******************************/
void set_position_servo(const mjModel* m,int actuator_no,double kp)
{
  m->actuator_gainprm[10*actuator_no+0]=kp;
  m->actuator_biasprm[10*actuator_no+1]=-kp;
}
/******************************/

/******************************/
void set_velocity_servo(const mjModel* m,int actuator_no,double kv)
{
  m->actuator_gainprm[10*actuator_no+0]=kv;
  m->actuator_biasprm[10*actuator_no+2]=-kv;
}
/******************************/

//**************************
void init_controller(const mjModel* m, mjData* d)
{

  int actuator_no;

  actuator_no = 0; //pservo-hip
  set_position_servo(m,actuator_no,100);

  actuator_no = 1; //vservo-hip
  set_velocity_servo(m,actuator_no,10);

  actuator_no = 2; //pservo-knee
  set_position_servo(m,actuator_no,1000);

  actuator_no = 3; //vservo-knee
  set_velocity_servo(m,actuator_no,0);

  fsm = fsm_air1;
  step_no = 0;
}

//**************************
void mycontroller(const mjModel* m, mjData* d)
{
  //write control here

  //Get data for transitions
  int body_no;
  int actuator_no;
  // body_no = 3;
  // printf("foot pos: %f %f %f \n", d->xpos[3*body_no + 0],d->xpos[3*body_no + 1],d->xpos[3*body_no + 2]);
  // printf("z velocity torso: %f \n",d->qvel[1]);
  // printf("********* \n");

  //all transitions
  body_no = 3;
  double z_foot = d->xpos[3*body_no + 2];
  double vz_torso = d->qvel[1];
  if (fsm==fsm_air1 && z_foot < 0.05 )
  {
    fsm = fsm_stance1;
    //printf("fsm_stance1 \n");
  }
  if (fsm== fsm_stance1 && vz_torso > 0)
  {
    fsm = fsm_stance2;
    //printf("fsm_stance2 \n");
  }
  if (fsm==fsm_stance2 && z_foot>0.05)
  {
    fsm = fsm_air2;
    //printf("fsm_air2 \n");
  }
  if (fsm==fsm_air2 && vz_torso < 0)
  {
    fsm = fsm_air1;
    //printf("fsm_air1 \n");
    step_no += 1;
    printf("step no = %d \n",step_no);
  }

  //all actions
  if (fsm == fsm_air1)
  {
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,100);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,10);

    //d->ctrl[0] = 0;
  }

  if (fsm == fsm_stance1)
  {
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,1000);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,0);
  }

  if (fsm == fsm_stance2)
  {
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,1050);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,0);

    d->ctrl[0] = -0.2;
  }

  if (fsm == fsm_air2)
  {
    actuator_no = 2; //pservo-knee
    set_position_servo(m,actuator_no,100);

    actuator_no = 3; //vservo-knee
    set_velocity_servo(m,actuator_no,10);

    d->ctrl[0] = 0;
  }

  //write data here (dont change/dete this function call; instead write what you need to save in save_data)
  if ( loop_index%data_frequency==0)
    {
      save_data(m,d);
    }
  loop_index = loop_index + 1;
}


//************************
// main function
int main(int argc, const char** argv)
{

    // activate software
    mj_activate("mjkey.txt");

    char xmlpath[100]={};
    char datapath[100]={};

    strcat(xmlpath,path);
    strcat(xmlpath,xmlfile);

    strcat(datapath,path);
    strcat(datapath,datafile);


    // load and compile model
    char error[1000] = "Could not load binary model";

    // check command-line arguments
    if( argc<2 )
        m = mj_loadXML(xmlpath, 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);

    // make data
    d = mj_makeData(m);


    // init GLFW
    if( !glfwInit() )
        mju_error("Could not initialize GLFW");

    // create window, make OpenGL context current, request v-sync
    GLFWwindow* window = glfwCreateWindow(1244, 700, "Demo", NULL, NULL);
    glfwMakeContextCurrent(window);
    glfwSwapInterval(1);

    // initialize visualization data structures
    mjv_defaultCamera(&cam);
    mjv_defaultOption(&opt);
    mjv_defaultScene(&scn);
    mjr_defaultContext(&con);
    mjv_makeScene(m, &scn, 2000);                // space for 2000 objects
    mjr_makeContext(m, &con, mjFONTSCALE_150);   // model-specific context

    // install GLFW mouse and keyboard callbacks
    glfwSetKeyCallback(window, keyboard);
    glfwSetCursorPosCallback(window, mouse_move);
    glfwSetMouseButtonCallback(window, mouse_button);
    glfwSetScrollCallback(window, scroll);

    double arr_view[] = {89.608063, -11.588379, 5, 0.000000, 0.000000, 2.000000}; //view the left side (for ll, lh, left_side)
    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];

    // install control callback
    mjcb_control = mycontroller;

    fid = fopen(datapath,"w");
    init_save_data();
    init_controller(m,d);

    // use the first while condition if you want to simulate for a period.
    while( !glfwWindowShouldClose(window))
    {
        // advance interactive simulation for 1/60 sec
        //  Assuming MuJoCo can simulate faster than real-time, which it usually can,
        //  this loop will finish on time for the next frame to be rendered at 60 fps.
        //  Otherwise add a cpu timer and exit this loop when it is time to render.
        mjtNum simstart = d->time;
        while( d->time - simstart < 1.0/60.0 )
        {
            mj_step(m, d);
        }

        if (d->time>=simend)
        {
           fclose(fid);
           break;
         }

       // get framebuffer viewport
        mjrRect viewport = {0, 0, 0, 0};
        glfwGetFramebufferSize(window, &viewport.width, &viewport.height);

        //opt.frame = mjFRAME_WORLD; //mjFRAME_BODY
        //opt.flags[mjVIS_COM]  = 1 ; //mjVIS_JOINT;
        //opt.flags[mjVIS_JOINT]  = 1 ;
          // update scene and render
        cam.lookat[0] = d->qpos[0];
        mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
        mjr_render(viewport, &scn, &con);
        //printf("{%f, %f, %f, %f, %f, %f};\n",cam.azimuth,cam.elevation, cam.distance,cam.lookat[0],cam.lookat[1],cam.lookat[2]);

        // swap OpenGL buffers (blocking call due to v-sync)
        glfwSwapBuffers(window);

        // process pending GUI events, call GLFW callbacks
        glfwPollEvents();

    }

    // free visualization storage
    mjv_freeScene(&scn);
    mjr_freeContext(&con);

    // free MuJoCo model and data, deactivate
    mj_deleteData(d);
    mj_deleteModel(m);
    mj_deactivate();

    // terminate GLFW (crashes with Linux NVidia drivers)
    #if defined(__APPLE__) || defined(_WIN32)
        glfwTerminate();
    #endif

    return 1;
}

  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值