//-----------------------------------//
// This file is part of MuJoCo. //
// Copyright (C) 2016 Roboti LLC. //
//-----------------------------------//
#pragma once
// cross-platform import
#if defined(MJ_STATIC)
#define MJAPI
#else
#if defined(_WIN32)
#define MJAPI __declspec(dllimport)
#else
#define MJAPI
#endif
#endif
// this is a C-API
#if defined(__cplusplus)
extern "C"
{
#endif
// header version; should match the library version as returned by mj_version()
#define mjVERSION_HEADER 131
// needed to define size_t, fabs and log10
#include "stdlib.h"
#include "math.h"
// type definitions
#include "mjmodel.h"
#include "mjdata.h"
#include "mjvisualize.h"
#include "mjrender.h"
// macros
#define mjMARKSTACK int _mark = d->pstack;
#define mjFREESTACK d->pstack = _mark;
#define mjDISABLED(x) (m->opt.disableflags & (x))
#define mjENABLED(x) (m->opt.enableflags & (x))
// user error and memory handlers
MJAPI extern void (*mju_user_error)(const char*);
MJAPI extern void (*mju_user_warning)(const char*);
MJAPI extern void* (*mju_user_malloc)(size_t);
MJAPI extern void (*mju_user_free)(void*);
// callbacks extending computation pipeline
MJAPI extern mjfGeneric mjcb_endstep;
MJAPI extern mjfGeneric mjcb_passive;
MJAPI extern mjfGeneric mjcb_control;
MJAPI extern mjfTime mjcb_time;
MJAPI extern mjfAct mjcb_act_dyn;
MJAPI extern mjfAct mjcb_act_gain;
MJAPI extern mjfAct mjcb_act_bias;
MJAPI extern mjfMagnetic mjcb_magnetic;
MJAPI extern mjfSolImp mjcb_sol_imp;
MJAPI extern mjfSolRef mjcb_sol_ref;
// collision function table
MJAPI extern mjfCollision mjCOLLISIONFUNC[mjNGEOMTYPES][mjNGEOMTYPES];
// string names
MJAPI extern const char* mjVISSTRING[mjNVISFLAG][3];
MJAPI extern const char* mjRNDSTRING[mjNRNDFLAG][3];
MJAPI extern const char* mjDISABLESTRING[mjNDISABLE];
MJAPI extern const char* mjENABLESTRING[mjNENABLE];
MJAPI extern const char* mjTIMERSTRING[mjNTIMER];
//---------------------- License activation and certificate (mutex-protected) -----------
// activate license, call mju_error on failure; return 1 if ok, 0 if failure
MJAPI int mj_activate(const char* filename);
// deactivate license, free memory
MJAPI void mj_deactivate(void);
// server: generate certificate question
MJAPI void mj_certQuestion(mjtNum question[16]);
// client: generate certificate answer given question
MJAPI void mj_certAnswer(const mjtNum question[16], mjtNum answer[16]);
// server: check certificate question-answer pair; return 1 if match, 0 if mismatch
MJAPI int mj_certCheck(const mjtNum question[16], const mjtNum answer[16]);
//---------------------- XML parser and C++ compiler (mutex-protected) ------------------
// parse XML file or string in MJCF or URDF format, compile it, return low-level model
// if xmlstring is not NULL, it has precedence over filename
// error can be NULL; otherwise assumed to have size error_sz
MJAPI mjModel* mj_loadXML(const char* filename, const char* xmlstring,
char* error, int error_sz);
// update XML data structures with info from low-level model, save as MJCF
// error can be NULL; otherwise assumed to have size error_sz
MJAPI int mj_saveXML(const char* filename, const mjModel* m, char* error, int error_sz);
// print internal XML schema as plain text or HTML, with style-padding or
MJAPI int mj_printSchema(const char* filename, char* buffer, int buffer_sz,
int flg_html, int flg_pad);
//---------------------- Main entry points ----------------------------------------------
// advance simulation: use control callback, no external force, RK4 available
MJAPI void mj_step(const mjModel* m, mjData* d);
// advance simulation in two steps: before external force/control is set by user
MJAPI void mj_step1(const mjModel* m, mjData* d);
// advance simulation in two steps: after external force/control is set by user
MJAPI void mj_step2(const mjModel* m, mjData* d);
// forward dynamics
MJAPI void mj_forward(const mjModel* m, mjData* d);
// inverse dynamics
MJAPI void mj_inverse(const mjModel* m, mjData* d);
// forward dynamics with skip: 0- no skip, 1- skip pos, 2- skip pos,vel
MJAPI void mj_forwardSkip(const mjModel* m, mjData* d, int skip);
// inverse dynamics with skip: 0- no skip, 1- skip pos, 2- skip pos,vel
MJAPI void mj_inverseSkip(const mjModel* m, mjData* d, int skip);
// sensor data
MJAPI void mj_sensor(const mjModel* m, mjData* d);
// energy
MJAPI void mj_energy(const mjModel* m, mjData* d);
//---------------------- Model and data initialization ----------------------------------
// set default solver paramters
MJAPI void mj_defaultSolRefImp(mjtNum* solref, mjtNum* solimp);
// set physics options to default values
MJAPI void mj_defaultOption(mjOption* opt);
// set visual options to default values
MJAPI void mj_defaultVisual(mjVisual* vis);
// copy mjModel; allocate new if dest is NULL
MJAPI mjModel* mj_copyModel(mjModel* dest, const mjModel* src);
// save model to binary file or memory buffer (buffer has precedence if szbuf>0)
MJAPI void mj_saveModel(const mjModel* m, const char* filename, void* buffer, int buffer_sz);
// load model from binary file or memory buffer (buffer has precedence if szbuf>0)
MJAPI mjModel* mj_loadModel(const char* filename, void* buffer, int buffer_sz);
// de-allocate model
MJAPI void mj_deleteModel(mjModel* m);
// size of buffer needed to hold model
MJAPI int mj_sizeModel(const mjModel* m);
// allocate mjData correponding to given model
MJAPI mjData* mj_makeData(const mjModel* m);
// copy mjData
MJAPI mjData* mj_copyData(mjData* dest, const mjModel* m, const mjData* src);
// set data to defaults
MJAPI void mj_resetData(const mjModel* m, mjData* d);
// set data to defaults, fill everything else with debug_value
MJAPI void mj_resetDataDebug(const mjModel* m, mjData* d, unsigned char debug_value);
// mjData stack allocate
MJAPI mjtNum* mj_stackAlloc(mjData* d, int size);
// de-allocate data
MJAPI void mj_deleteData(mjData* d);
// reset callbacks to defaults
MJAPI void mj_resetCallbacks(void);
// set constant fields of mjModel
MJAPI void mj_setConst(mjModel* m, mjData* d, int flg_actrange);
//---------------------- Printing -------------------------------------------------------
// print model to text file
MJAPI void mj_printModel(const mjModel* m, const char* filename);
// print data to text file
MJAPI void mj_printData(const mjModel* m, mjData* d, const char* filename);
// print matrix to screen
MJAPI void mju_printMat(const mjtNum* mat, int nr, int nc);
//---------------------- Components: forward dynamics -----------------------------------
// position-dependent computations
MJAPI void mj_fwdPosition(const mjModel* m, mjData* d);
// velocity-dependent computations
MJAPI void mj_fwdVelocity(const mjModel* m, mjData* d);
// compute actuator force
MJAPI void mj_fwdActuation(const mjModel* m, mjData* d);
// add up all non-constraint forces, compute qacc_unc
MJAPI void mj_fwdAcceleration(const mjModel* m, mjData* d);
// constraint solver
MJAPI void mj_fwdConstraint(const mjModel* m, mjData* d);
// Euler integrator, semi-implicit in velocity
MJAPI void mj_Euler(const mjModel* m, mjData* d);
// Runge-Kutta explicit order-N integrator
MJAPI void mj_RungeKutta(const mjModel* m, mjData* d, int N);
//---------------------- Components: inverse dynamics -----------------------------------
// position-dependent computations
MJAPI void mj_invPosition(const mjModel* m, mjData* d);
// velocity-dependent computations
MJAPI void mj_invVelocity(const mjModel* m, mjData* d);
// constraint solver
MJAPI void mj_invConstraint(const mjModel* m, mjData* d);
// compare forward and inverse dynamics, without changing results of forward dynamics
MJAPI void mj_compareFwdInv(const mjModel* m, mjData* d);
//---------------------- Sub-components of the computation pipeline ---------------------
// check positions; reset if bad
MJAPI void mj
没有合适的资源?快使用搜索试试~ 我知道了~
LOTS的已经通过的最初版本,但是mu未更改
共2000个文件
py:1002个
txt:801个
json:147个
需积分: 0 0 下载量 181 浏览量
2024-01-30
22:52:22
上传
评论
收藏 102.97MB ZIP 举报
温馨提示
LOTS的已经通过的最初版本,但是mu未更改
资源推荐
资源详情
资源评论
收起资源包目录
LOTS的已经通过的最初版本,但是mu未更改 (2000个子文件)
mujoco.h 29KB
fuhua_4770.json 2.4MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
roadnet_6_6.json 1.91MB
anon_1_33_fuhua_4_27_24hto1w_4089.json 1.87MB
anon_1_33_fuhua_24hto1w_2490.json 1.32MB
fuhua_2570.json 1.29MB
anon_6_6_small_2570_bi.json 1.2MB
fuhua_real_1775.json 818KB
anon_1_33_fuhua_0.4x24hto1h.json 818KB
fuhua_cityflow.json 694KB
roadnet_1_33.json 656KB
roadnet_1_33.json 656KB
rollout.json 264KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
anon_6_6_300_0.3_bi.json 11KB
共 2000 条
- 1
- 2
- 3
- 4
- 5
- 6
- 20
资源评论
qq_46362810
- 粉丝: 0
- 资源: 2
上传资源 快速赚钱
- 我的内容管理 展开
- 我的资源 快来上传第一个资源
- 我的收益 登录查看自己的收益
- 我的积分 登录查看自己的积分
- 我的C币 登录后查看C币余额
- 我的收藏
- 我的下载
- 下载帮助
最新资源
- 适用于中小型游戏的通用排行榜后台系统.zip
- 一秒99条的短信接口.zip
- 基于jsp+servlet+mysql的javaweb健身房俱乐部系统
- 110_c6ce6db7048c08aee35a7a2675732d54.apk (1).1
- sql查询数据库表结构(sql server适用)
- HTTP CLENT处理加密证书程序参考
- update9-20240601.5.205.slice.img.7z.002
- 微信小程序优惠券页面前端模板源码
- 林子雨编著《Spark编程基础(Python版)》 实验7 Spark机器学习库MLib编程实践数据
- 一种支持微信文本限制长度限制使用的,在合适的位置截取限制字节长度的字符串子串的java算法
资源上传下载、课程学习等过程中有任何疑问或建议,欢迎提出宝贵意见哦~我们会及时处理!
点击此处反馈
安全验证
文档复制为VIP权益,开通VIP直接复制
信息提交成功