PKG - Update Mujoco to 3.2.2

This commit is contained in:
JB Briant
2025-05-09 14:31:04 +07:00
parent 385f38cd8d
commit 37fa683842
34 changed files with 139 additions and 17430 deletions

View File

@ -25,7 +25,7 @@ public class Mujoco : ModuleRules
PublicAdditionalLibraries.Add(DllPath);
RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "mujoco.dylib"), DllPath);
RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "libmujoco.3.2.7.dylib"), DllPath);
RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "libmujoco.3.3.2.dylib"), DllPath);
// RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "../../../../", "MacOS/libmujoco.3.2.7.dylib"), DllPath);
// RuntimeDependencies.Add("$(BinaryOutputDir)/UnrealEditor.app/Contents/MacOS/libmujoco.3.2.7.dylib", DllPath);
// Console.WriteLine("$BinaryOutputDir:"+ BinaryOutputDir);
@ -33,7 +33,7 @@ public class Mujoco : ModuleRules
// Console.WriteLine("$Target.Name:"+ Target.Name);
RuntimeDependencies.Add($"$(BinaryOutputDir)/libmujoco.3.2.7.dylib", DllPath);
RuntimeDependencies.Add($"$(BinaryOutputDir)/libmujoco.3.3.2.dylib", DllPath);
// throw new Exception("test");
}
@ -43,7 +43,7 @@ public class Mujoco : ModuleRules
PublicAdditionalLibraries.Add(DllPath);
PublicDelayLoadDLLs.Add(DllPath);
RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "libmujoco.so"), DllPath);
RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "libmujoco.so.3.2.7"), DllPath);
RuntimeDependencies.Add(Path.Combine("$(TargetOutputDir)", "libmujoco.so.3.3.2"), DllPath);
}
}
}

File diff suppressed because it is too large Load Diff

View File

@ -182,7 +182,6 @@ struct mjData_ {
// solver statistics
mjSolverStat solver[mjNISLAND*mjNSOLVER]; // solver statistics per island, per iteration
int solver_nisland; // number of islands processed by solver
int solver_niter[mjNISLAND]; // number of solver iterations, per island
int solver_nnz[mjNISLAND]; // number of nonzeros in Hessian or efc_AR, per island
mjtNum solver_fwdinv[2]; // forward-inverse comparison: qfrc, efc
@ -340,6 +339,10 @@ struct mjData_ {
int* B_rownnz; // body-dof: non-zeros in each row (nbody x 1)
int* B_rowadr; // body-dof: address of each row in B_colind (nbody x 1)
int* B_colind; // body-dof: column indices of non-zeros (nB x 1)
int* M_rownnz; // inertia: non-zeros in each row (nv x 1)
int* M_rowadr; // inertia: address of each row in M_colind (nv x 1)
int* M_colind; // inertia: column indices of non-zeros (nM x 1)
int* mapM2M; // index mapping from M (legacy) to M (CSR) (nM x 1)
int* C_rownnz; // reduced dof-dof: non-zeros in each row (nv x 1)
int* C_rowadr; // reduced dof-dof: address of each row in C_colind (nv x 1)
int* C_colind; // reduced dof-dof: column indices of non-zeros (nC x 1)
@ -371,8 +374,8 @@ struct mjData_ {
mjtNum* qfrc_constraint; // constraint force (nv x 1)
// computed by mj_inverse
mjtNum* qfrc_inverse; // net external force; should equal: (nv x 1)
// qfrc_applied + J'*xfrc_applied + qfrc_actuator
mjtNum* qfrc_inverse; // net external force; should equal:
// qfrc_applied + J'*xfrc_applied + qfrc_actuator (nv x 1)
// computed by mj_sensorAcc/mj_rnePostConstraint if needed; rotation:translation format
mjtNum* cacc; // com-based acceleration (nbody x 6)
@ -438,6 +441,9 @@ struct mjData_ {
// thread pool pointer
uintptr_t threadpool;
// compilation signature
uint64_t signature; // also held by the mjSpec that compiled the model
};
typedef struct mjData_ mjData;

View File

@ -29,6 +29,7 @@
#define mjMAXIMP 0.9999 // maximum constraint impedance
#define mjMAXCONPAIR 50 // maximum number of contacts per geom pair
#define mjMAXTREEDEPTH 50 // maximum bounding volume hierarchy depth
#define mjMAXFLEXNODES 27 // maximum number of flex nodes
//---------------------------------- sizes ---------------------------------------------------------
@ -43,6 +44,7 @@
#define mjNSOLVER 200 // size of one mjData.solver array
#define mjNISLAND 20 // number of mjData.solver arrays
//---------------------------------- enum types (mjt) ----------------------------------------------
typedef enum mjtDisableBit_ { // disable default feature bitflags
@ -62,8 +64,9 @@ typedef enum mjtDisableBit_ { // disable default feature bitflags
mjDSBL_MIDPHASE = 1<<13, // mid-phase collision filtering
mjDSBL_EULERDAMP = 1<<14, // implicit integration of joint damping in Euler integrator
mjDSBL_AUTORESET = 1<<15, // automatic reset when numerical issues are detected
mjDSBL_NATIVECCD = 1<<16, // native convex collision detection
mjNDISABLE = 16 // number of disable flags
mjNDISABLE = 17 // number of disable flags
} mjtDisableBit;
@ -75,9 +78,8 @@ typedef enum mjtEnableBit_ { // enable optional feature bitflags
// experimental features:
mjENBL_MULTICCD = 1<<4, // multi-point convex collision detection
mjENBL_ISLAND = 1<<5, // constraint island discovery
mjENBL_NATIVECCD = 1<<6, // native convex collision detection
mjNENABLE = 7 // number of enable flags
mjNENABLE = 6 // number of enable flags
} mjtEnableBit;
@ -266,7 +268,10 @@ typedef enum mjtObj_ { // type of MujoCo object
mjNOBJECT, // number of object types
// meta elements, do not appear in mjModel
mjOBJ_FRAME = 100 // frame
mjOBJ_FRAME = 100, // frame
mjOBJ_DEFAULT, // default
mjOBJ_MODEL // entire model
} mjtObj;
@ -312,6 +317,7 @@ typedef enum mjtSensor_ { // type of sensor
mjSENS_ACTUATORVEL, // scalar actuator velocity
mjSENS_ACTUATORFRC, // scalar actuator force
mjSENS_JOINTACTFRC, // scalar actuator force, measured at the joint
mjSENS_TENDONACTFRC, // scalar actuator force, measured at the tendon
// sensors related to ball joints
mjSENS_BALLQUAT, // 4D ball joint quaternion
@ -347,6 +353,8 @@ typedef enum mjtSensor_ { // type of sensor
mjSENS_GEOMFROMTO, // segment between two geoms
// global sensors
mjSENS_E_POTENTIAL, // potential energy
mjSENS_E_KINETIC, // kinetic energy
mjSENS_CLOCK, // simulation time
// plugin-controlled sensors
@ -605,6 +613,7 @@ struct mjModel_ {
int ncam; // number of cameras
int nlight; // number of lights
int nflex; // number of flexes
int nflexnode; // number of dofs in all flexes
int nflexvert; // number of vertices in all flexes
int nflexedge; // number of edges in all flexes
int nflexelem; // number of elements in all flexes
@ -619,6 +628,9 @@ struct mjModel_ {
int nmeshtexcoord; // number of texcoords in all meshes
int nmeshface; // number of triangular faces in all meshes
int nmeshgraph; // number of ints in mesh auxiliary data
int nmeshpoly; // number of polygons in all meshes
int nmeshpolyvert; // number of vertices in all polygons
int nmeshpolymap; // number of polygons in vertex map
int nskin; // number of skins
int nskinvert; // number of vertices in all skins
int nskintexvert; // number of vertiex with texcoords in all skins
@ -781,9 +793,7 @@ struct mjModel_ {
mjtNum* geom_aabb; // bounding box, (center, size) (ngeom x 6)
mjtNum* geom_rbound; // radius of bounding sphere (ngeom x 1)
mjtNum* geom_pos; // local position offset rel. to body (ngeom x 3)
mjtNum* geom_spos; // spec local position offset rel. to body (ngeom x 3)
mjtNum* geom_quat; // local orientation offset rel. to body (ngeom x 4)
mjtNum* geom_squat; // spec local orientation offset rel. body (ngeom x 4)
mjtNum* geom_friction; // friction for (slide, spin, roll) (ngeom x 3)
mjtNum* geom_margin; // detect contact if dist<margin (ngeom x 1)
mjtNum* geom_gap; // include in solver if dist<margin-gap (ngeom x 1)
@ -859,6 +869,9 @@ struct mjModel_ {
int* flex_dim; // 1: lines, 2: triangles, 3: tetrahedra (nflex x 1)
int* flex_matid; // material id for rendering (nflex x 1)
int* flex_group; // group for visibility (nflex x 1)
int* flex_interp; // interpolation (0: vertex, 1: nodes) (nflex x 1)
int* flex_nodeadr; // first node address (nflex x 1)
int* flex_nodenum; // number of nodes (nflex x 1)
int* flex_vertadr; // first vertex address (nflex x 1)
int* flex_vertnum; // number of vertices (nflex x 1)
int* flex_edgeadr; // first edge address (nflex x 1)
@ -872,15 +885,19 @@ struct mjModel_ {
int* flex_evpairadr; // first evpair address (nflex x 1)
int* flex_evpairnum; // number of evpairs (nflex x 1)
int* flex_texcoordadr; // address in flex_texcoord; -1: none (nflex x 1)
int* flex_nodebodyid; // node body ids (nflexnode x 1)
int* flex_vertbodyid; // vertex body ids (nflexvert x 1)
int* flex_edge; // edge vertex ids (2 per edge) (nflexedge x 2)
int* flex_elem; // element vertex ids (dim+1 per elem) (nflexelemdata x 1)
int* flex_elemtexcoord; // element texture coordinates (dim+1) (nflexelemdata x 1)
int* flex_elemedge; // element edge ids (nflexelemedge x 1)
int* flex_elemlayer; // element distance from surface, 3D only (nflexelem x 1)
int* flex_shell; // shell fragment vertex ids (dim per frag) (nflexshelldata x 1)
int* flex_evpair; // (element, vertex) collision pairs (nflexevpair x 2)
mjtNum* flex_vert; // vertex positions in local body frames (nflexvert x 3)
mjtNum* flex_vert0; // vertex positions in qpos0 on [0, 1]^d (nflexvert x 3)
mjtNum* flex_node; // node positions in local body frames (nflexnode x 3)
mjtNum* flex_node0; // Cartesian node positions in qpos0 (nflexnode x 3)
mjtNum* flexedge_length0; // edge lengths in qpos0 (nflexedge x 1)
mjtNum* flexedge_invweight0; // edge inv. weight in qpos0 (nflexedge x 1)
mjtNum* flex_radius; // radius around primitive element (nflex x 1)
@ -921,6 +938,15 @@ struct mjModel_ {
mjtNum* mesh_pos; // translation applied to asset vertices (nmesh x 3)
mjtNum* mesh_quat; // rotation applied to asset vertices (nmesh x 4)
int* mesh_pathadr; // address of asset path for mesh; -1: none (nmesh x 1)
int* mesh_polynum; // number of polygons per mesh (nmesh x 1)
int* mesh_polyadr; // first polygon address per mesh (nmesh x 1)
mjtNum* mesh_polynormal; // all polygon normals (nmeshpoly x 3)
int* mesh_polyvertadr; // polygon vertex start address (nmeshpoly x 1)
int* mesh_polyvertnum; // number of vertices per polygon (nmeshpoly x 1)
int* mesh_polyvert; // all polygon vertices (nmeshpolyvert x 1)
int* mesh_polymapadr; // first polygon address per vertex (nmeshvert x 1)
int* mesh_polymapnum; // number of polygons per vertex (nmeshvert x 1)
int* mesh_polymap; // vertex to polygon map (nmeshpolymap x 1)
// skins
int* skin_matid; // skin material id; -1: none (nskin x 1)
@ -1006,15 +1032,18 @@ struct mjModel_ {
int* tendon_matid; // material id for rendering (ntendon x 1)
int* tendon_group; // group for visibility (ntendon x 1)
mjtByte* tendon_limited; // does tendon have length limits (ntendon x 1)
mjtByte* tendon_actfrclimited; // does tendon have actuator force limits (ntendon x 1)
mjtNum* tendon_width; // width for rendering (ntendon x 1)
mjtNum* tendon_solref_lim; // constraint solver reference: limit (ntendon x mjNREF)
mjtNum* tendon_solimp_lim; // constraint solver impedance: limit (ntendon x mjNIMP)
mjtNum* tendon_solref_fri; // constraint solver reference: friction (ntendon x mjNREF)
mjtNum* tendon_solimp_fri; // constraint solver impedance: friction (ntendon x mjNIMP)
mjtNum* tendon_range; // tendon length limits (ntendon x 2)
mjtNum* tendon_actfrcrange; // range of total actuator force (ntendon x 2)
mjtNum* tendon_margin; // min distance for limit detection (ntendon x 1)
mjtNum* tendon_stiffness; // stiffness coefficient (ntendon x 1)
mjtNum* tendon_damping; // damping coefficient (ntendon x 1)
mjtNum* tendon_armature; // inertia associated with tendon velocity (ntendon x 1)
mjtNum* tendon_frictionloss; // loss due to friction (ntendon x 1)
mjtNum* tendon_lengthspring; // spring resting length range (ntendon x 2)
mjtNum* tendon_length0; // tendon length in qpos0 (ntendon x 1)
@ -1131,6 +1160,9 @@ struct mjModel_ {
// paths
char* paths; // paths to assets, 0-terminated (npaths x 1)
// compilation signature
uint64_t signature; // also held by the mjSpec that compiled this model
};
typedef struct mjModel_ mjModel;

View File

@ -48,7 +48,7 @@ typedef void (*mjfGetResourceDir)(mjResource* resource, const char** dir, int* n
// callback for checking if the current resource was modified from the time
// specified by the timestamp
// returns 0 if the resource's timestamp matches the provided timestamp
// returns > 0 if the the resource is younger than the given timestamp
// returns > 0 if the resource is younger than the given timestamp
// returns < 0 if the resource is older than the given timestamp
typedef int (*mjfResourceModified)(const mjResource* resource, const char* timestamp);

View File

@ -23,6 +23,7 @@
// this is a C-API
#ifdef __cplusplus
#include <cstddef>
#include <cstdint>
#include <string>
#include <vector>
@ -62,10 +63,11 @@ typedef enum mjtGeomInertia_ { // type of inertia inference
} mjtGeomInertia;
typedef enum mjtMeshInertia_ { // type of mesh inertia
mjINERTIA_CONVEX = 0, // convex mesh inertia
mjINERTIA_EXACT, // exact mesh inertia
mjINERTIA_LEGACY, // legacy mesh inertia
typedef enum mjtMeshInertia_ { // type of mesh inertia
mjMESH_INERTIA_CONVEX = 0, // convex mesh inertia
mjMESH_INERTIA_EXACT, // exact mesh inertia
mjMESH_INERTIA_LEGACY, // legacy mesh inertia
mjMESH_INERTIA_SHELL // shell mesh inertia
} mjtMeshInertia;
@ -118,6 +120,7 @@ typedef enum mjtOrientation_ { // type of orientation specifier
typedef struct mjsElement_ { // element type, do not modify
mjtObj elemtype; // element type
uint64_t signature; // compilation signature
} mjsElement;
@ -135,6 +138,7 @@ typedef struct mjsCompiler_ { // compiler options
mjtByte fusestatic; // fuse static bodies with parent
int inertiafromgeom; // use geom inertias (mjtInertiaFromGeom)
int inertiagrouprange[2]; // range of geom groups used to compute inertia
mjtByte saveinertial; // save explicit inertial clause for all bodies to XML
int alignfree; // align free joints with inertial frame
mjLROpt LRopt; // options for lengthrange computation
} mjsCompiler;
@ -439,10 +443,13 @@ typedef struct mjsFlex_ { // flex specification
double thickness; // thickness (2D only)
// mesh properties
mjStringVec* nodebody; // node body names
mjStringVec* vertbody; // vertex body names
mjDoubleVec* node; // node positions
mjDoubleVec* vert; // vertex positions
mjIntVec* elem; // element vertex ids
mjFloatVec* texcoord; // vertex texture coordinates
mjIntVec* elemtexcoord; // element texture coordinates
// other
mjString* info; // message appended to compiler errors
@ -457,7 +464,7 @@ typedef struct mjsMesh_ { // mesh specification
double refpos[3]; // reference position
double refquat[4]; // reference orientation
double scale[3]; // rescale mesh
mjtMeshInertia inertia; // inertia type (convex, legacy, exact)
mjtMeshInertia inertia; // inertia type (convex, legacy, exact, shell)
mjtByte smoothnormal; // do not exclude large-angle faces from normals
int maxhullvert; // maximum vertex count for the convex hull
mjFloatVec* uservert; // user vertex data
@ -610,17 +617,20 @@ typedef struct mjsTendon_ { // tendon specification
mjsElement* element; // element type
mjString* name; // name
// stiffness, damping, friction
// stiffness, damping, friction, armature
double stiffness; // stiffness coefficient
double springlength[2]; // spring resting length; {-1, -1}: use qpos_spring
double damping; // damping coefficient
double frictionloss; // friction loss
mjtNum solref_friction[mjNREF]; // solver reference: tendon friction
mjtNum solimp_friction[mjNIMP]; // solver impedance: tendon friction
double armature; // inertia associated with tendon velocity
// length range
int limited; // does tendon have limits (mjtLimited)
int actfrclimited; // does tendon have actuator force limits
double range[2]; // length limits
double actfrcrange[2]; // actuator force limits
double margin; // margin value for tendon limit detection
mjtNum solref_limit[mjNREF]; // solver reference: tendon limits
mjtNum solimp_limit[mjNIMP]; // solver impedance: tendon limits

View File

@ -516,9 +516,14 @@ struct mjvSceneState_ {
int* flex_dim;
int* flex_matid;
int* flex_group;
int* flex_interp;
int* flex_nodeadr;
int* flex_nodenum;
int* flex_nodebodyid;
int* flex_vertadr;
int* flex_vertnum;
int* flex_elem;
int* flex_elemtexcoord;
int* flex_elemlayer;
int* flex_elemadr;
int* flex_elemnum;
@ -529,8 +534,11 @@ struct mjvSceneState_ {
int* flex_texcoordadr;
int* flex_bvhadr;
int* flex_bvhnum;
mjtByte* flex_centered;
mjtNum* flex_node;
mjtNum* flex_radius;
float* flex_rgba;
float* flex_texcoord;
int* hfield_pathadr;
@ -585,8 +593,10 @@ struct mjvSceneState_ {
int* tendon_matid;
int* tendon_group;
mjtByte* tendon_limited;
mjtByte* tendon_actfrclimited;
mjtNum* tendon_width;
mjtNum* tendon_range;
mjtNum* tendon_actfrcrange;
mjtNum* tendon_stiffness;
mjtNum* tendon_damping;
mjtNum* tendon_frictionloss;

View File

@ -1,65 +0,0 @@
#ifndef MUJOCO_MJWRAPPER_H_
#define MUJOCO_MJWRAPPER_H_
#include <functional>
#include <memory>
#include <mujoco/mujoco.h>
namespace tinyxml2 {
class XMLDocument;
class XMLElement;
} // namespace tinyxml2
struct mjVec_t {
mjtNum x, y, z;
mjVec_t() : x(0), y(0), z(0) {}
mjVec_t(mjtNum x, mjtNum y, mjtNum z) : x(x), y(y), z(z) {}
std::string ToString() const {
return std::to_string(x) + " " + std::to_string(y) + " " +
std::to_string(z);
}
};
struct mjQuat_t {
double x, y, z, w;
mjQuat_t() : x(0), y(0), z(0), w(1) {}
mjQuat_t(mjtNum x, mjtNum y, mjtNum z, mjtNum w) : x(x), y(y), z(z), w(w) {}
std::string ToString() const {
return std::to_string(w) + " " + std::to_string(x) + " " +
std::to_string(y) + " " + std::to_string(z);
}
};
class FMujocoWrapper {
std::unique_ptr<mjSpec, std::function<void(mjSpec *)>> Spec;
std::unique_ptr<tinyxml2::XMLDocument> XmlDoc;
std::unique_ptr<mjVFS> Vfs;
tinyxml2::XMLElement *RootElement;
tinyxml2::XMLElement *AssetsElement;
public:
MJAPI FMujocoWrapper();
MJAPI ~FMujocoWrapper();
MJAPI void ParseXml(const std::string &xml_string);
MJAPI void AppendXml(const std::string &xml_string,
const std::string &base_path,
const std::string &file_name,
const std::string &model_name,
const std::string &prefix,
bool is_static, const mjVec_t &pos,
const mjQuat_t &quat);
MJAPI void RemoveBody(const std::string &body_name);
MJAPI void AppendBinary(const std::vector<uint8_t>& buffer, const std::string &prefix);
MJAPI mjModel *Compile();
};
#endif // MUJOCO_MJWRAPPER_H_

View File

@ -81,6 +81,7 @@
XMJV( ncam ) \
XMJV( nlight ) \
XMJV( nflex ) \
X ( nflexnode ) \
XMJV( nflexvert ) \
X ( nflexedge ) \
X ( nflexelem ) \
@ -95,6 +96,9 @@
X ( nmeshtexcoord ) \
X ( nmeshface ) \
X ( nmeshgraph ) \
X ( nmeshpoly ) \
X ( nmeshpolyvert ) \
X ( nmeshpolymap ) \
XMJV( nskin ) \
XMJV( nskinvert ) \
X ( nskintexvert ) \
@ -260,9 +264,7 @@
XMJV( mjtNum, geom_aabb, ngeom, 6 ) \
XMJV( mjtNum, geom_rbound, ngeom, 1 ) \
X ( mjtNum, geom_pos, ngeom, 3 ) \
X ( mjtNum, geom_spos, ngeom, 3 ) \
X ( mjtNum, geom_quat, ngeom, 4 ) \
X ( mjtNum, geom_squat, ngeom, 4 ) \
X ( mjtNum, geom_friction, ngeom, 3 ) \
X ( mjtNum, geom_margin, ngeom, 1 ) \
X ( mjtNum, geom_gap, ngeom, 1 ) \
@ -328,6 +330,9 @@
XMJV( int, flex_dim, nflex, 1 ) \
XMJV( int, flex_matid, nflex, 1 ) \
XMJV( int, flex_group, nflex, 1 ) \
XMJV( int, flex_interp, nflex, 1 ) \
XMJV( int, flex_nodeadr, nflex, 1 ) \
XMJV( int, flex_nodenum, nflex, 1 ) \
XMJV( int, flex_vertadr, nflex, 1 ) \
XMJV( int, flex_vertnum, nflex, 1 ) \
X ( int, flex_edgeadr, nflex, 1 ) \
@ -341,15 +346,19 @@
X ( int, flex_evpairadr, nflex, 1 ) \
X ( int, flex_evpairnum, nflex, 1 ) \
XMJV( int, flex_texcoordadr, nflex, 1 ) \
XMJV( int, flex_nodebodyid, nflexnode, 1 ) \
X ( int, flex_vertbodyid, nflexvert, 1 ) \
X ( int, flex_edge, nflexedge, 2 ) \
XMJV( int, flex_elem, nflexelemdata, 1 ) \
XMJV( int, flex_elemtexcoord, nflexelemdata, 1 ) \
X ( int, flex_elemedge, nflexelemedge, 1 ) \
XMJV( int, flex_elemlayer, nflexelem, 1 ) \
XMJV( int, flex_shell, nflexshelldata,1 ) \
X ( int, flex_evpair, nflexevpair, 2 ) \
X ( mjtNum, flex_vert, nflexvert, 3 ) \
X ( mjtNum, flex_vert0, nflexvert, 3 ) \
XMJV( mjtNum, flex_node, nflexnode, 3 ) \
X ( mjtNum, flex_node0, nflexnode, 3 ) \
X ( mjtNum, flexedge_length0, nflexedge, 1 ) \
X ( mjtNum, flexedge_invweight0, nflexedge, 1 ) \
XMJV( mjtNum, flex_radius, nflex, 1 ) \
@ -360,12 +369,12 @@
X ( mjtByte, flex_edgeequality, nflex, 1 ) \
X ( mjtByte, flex_rigid, nflex, 1 ) \
X ( mjtByte, flexedge_rigid, nflexedge, 1 ) \
X ( mjtByte, flex_centered, nflex, 1 ) \
XMJV( mjtByte, flex_centered, nflex, 1 ) \
XMJV( mjtByte, flex_flatskin, nflex, 1 ) \
XMJV( int, flex_bvhadr, nflex, 1 ) \
XMJV( int, flex_bvhnum, nflex, 1 ) \
XMJV( float, flex_rgba, nflex, 4 ) \
X ( float, flex_texcoord, nflextexcoord, 2 ) \
XMJV( float, flex_texcoord, nflextexcoord, 2 ) \
X ( int, mesh_vertadr, nmesh, 1 ) \
X ( int, mesh_vertnum, nmesh, 1 ) \
X ( int, mesh_normaladr, nmesh, 1 ) \
@ -388,6 +397,15 @@
XNV ( int, mesh_facetexcoord, nmeshface, 3 ) \
XNV ( int, mesh_graph, nmeshgraph, 1 ) \
XMJV( int, mesh_pathadr, nmesh, 1 ) \
X ( int, mesh_polynum, nmesh, 1 ) \
X ( int, mesh_polyadr, nmesh, 1 ) \
X ( mjtNum, mesh_polynormal, nmeshpoly, 3 ) \
X ( int, mesh_polyvertadr, nmeshpoly, 1 ) \
X ( int, mesh_polyvertnum, nmeshpoly, 1 ) \
X ( int, mesh_polyvert, nmeshpolyvert, 1 ) \
X ( int, mesh_polymapadr, nmeshvert, 1 ) \
X ( int, mesh_polymapnum, nmeshvert, 1 ) \
X ( int, mesh_polymap, nmeshpolymap, 1 ) \
XMJV( int, skin_matid, nskin, 1 ) \
XMJV( int, skin_group, nskin, 1 ) \
XMJV( float, skin_rgba, nskin, 4 ) \
@ -457,15 +475,18 @@
XMJV( int, tendon_matid, ntendon, 1 ) \
XMJV( int, tendon_group, ntendon, 1 ) \
XMJV( mjtByte, tendon_limited, ntendon, 1 ) \
XMJV( mjtByte, tendon_actfrclimited, ntendon, 1 ) \
XMJV( mjtNum, tendon_width, ntendon, 1 ) \
X ( mjtNum, tendon_solref_lim, ntendon, mjNREF ) \
X ( mjtNum, tendon_solimp_lim, ntendon, mjNIMP ) \
X ( mjtNum, tendon_solref_fri, ntendon, mjNREF ) \
X ( mjtNum, tendon_solimp_fri, ntendon, mjNIMP ) \
XMJV( mjtNum, tendon_range, ntendon, 2 ) \
XMJV( mjtNum, tendon_actfrcrange, ntendon, 2 ) \
X ( mjtNum, tendon_margin, ntendon, 1 ) \
XMJV( mjtNum, tendon_stiffness, ntendon, 1 ) \
XMJV( mjtNum, tendon_damping, ntendon, 1 ) \
X ( mjtNum, tendon_armature, ntendon, 1 ) \
XMJV( mjtNum, tendon_frictionloss, ntendon, 1 ) \
XMJV( mjtNum, tendon_lengthspring, ntendon, 2 ) \
X ( mjtNum, tendon_length0, ntendon, 1 ) \
@ -654,6 +675,10 @@
X ( int, B_rownnz, nbody, 1 ) \
X ( int, B_rowadr, nbody, 1 ) \
X ( int, B_colind, nB, 1 ) \
X ( int, M_rownnz, nv, 1 ) \
X ( int, M_rowadr, nv, 1 ) \
X ( int, M_colind, nM, 1 ) \
X ( int, mapM2M, nM, 1 ) \
X ( int, C_rownnz, nv, 1 ) \
X ( int, C_rowadr, nv, 1 ) \
X ( int, C_colind, nC, 1 ) \
@ -752,7 +777,6 @@
X( size_t, maxuse_arena ) \
X( int, maxuse_con ) \
X( int, maxuse_efc ) \
X( int, solver_nisland ) \
X( int, ncon ) \
X( int, ne ) \
X( int, nf ) \

View File

@ -16,7 +16,7 @@
#define MUJOCO_MUJOCO_H_
// header version; should match the library version as returned by mj_version()
#define mjVERSION_HEADER 327
#define mjVERSION_HEADER 332
// needed to define size_t, fabs and log10
#include <stdlib.h>
@ -110,7 +110,7 @@ MJAPI mjModel* mj_compile(mjSpec* s, const mjVFS* vfs);
// Recompile spec to model, preserving the state, return 0 on success.
MJAPI int mj_recompile(mjSpec* s, const mjVFS* vfs, mjModel* m, mjData* d);
// Update XML data structures with info from low-level model, save as MJCF.
// Update XML data structures with info from low-level model created with mj_loadXML, save as MJCF.
// If error is not NULL, it must have size error_sz.
MJAPI int mj_saveLastXML(const char* filename, const mjModel* m, char* error, int error_sz);
@ -173,9 +173,6 @@ MJAPI void mj_saveModel(const mjModel* m, const char* filename, void* buffer, in
// If vfs is not NULL, look up file in vfs before reading from disk.
MJAPI mjModel* mj_loadModel(const char* filename, const mjVFS* vfs);
// Load model from memory buffer.
MJAPI mjModel *mj_loadModelBuffer(const void *buffer, int buffer_sz);
// Free memory allocation in model.
MJAPI void mj_deleteModel(mjModel* m);
@ -245,6 +242,9 @@ MJAPI void mj_deleteSpec(mjSpec* s);
// Activate plugin. Returns 0 on success.
MJAPI int mjs_activatePlugin(mjSpec* s, const char* name);
// Turn deep copy on or off attach. Returns 0 on success.
MJAPI int mjs_setDeepCopy(mjSpec* s, int deepcopy);
//---------------------------------- Printing ------------------------------------------------------
@ -257,11 +257,11 @@ MJAPI void mj_printModel(const mjModel* m, const char* filename);
// Print mjData to text file, specifying format.
// float_format must be a valid printf-style format string for a single float value
MJAPI void mj_printFormattedData(const mjModel* m, mjData* d, const char* filename,
MJAPI void mj_printFormattedData(const mjModel* m, const mjData* d, const char* filename,
const char* float_format);
// Print data to text file.
MJAPI void mj_printData(const mjModel* m, mjData* d, const char* filename);
MJAPI void mj_printData(const mjModel* m, const mjData* d, const char* filename);
// Print matrix to screen.
MJAPI void mju_printMat(const mjtNum* mat, int nr, int nc);
@ -1125,8 +1125,8 @@ MJAPI void mju_quatIntegrate(mjtNum quat[4], const mjtNum vel[3], mjtNum scale);
// Construct quaternion performing rotation from z-axis to given vector.
MJAPI void mju_quatZ2Vec(mjtNum quat[4], const mjtNum vec[3]);
// extract 3D rotation from an arbitrary 3x3 matrix by refining the input quaternion
// returns the number of iterations required to converge
// Extract 3D rotation from an arbitrary 3x3 matrix by refining the input quaternion.
// Returns the number of iterations required to converge
MJAPI int mju_mat2Rot(mjtNum quat[4], const mjtNum mat[9]);
// Convert sequence of Euler angles (radians) to quaternion.
@ -1414,21 +1414,15 @@ MJAPI void mju_taskJoin(mjTask* task);
//---------------------------------- Attachment ----------------------------------------------------
// Attach child body to a parent frame, return the attached body if success or NULL otherwise.
MJAPI mjsBody* mjs_attachBody(mjsFrame* parent, const mjsBody* child,
const char* prefix, const char* suffix);
// Attach child to a parent, return the attached element if success or NULL otherwise.
MJAPI mjsElement* mjs_attach(mjsElement* parent, const mjsElement* child,
const char* prefix, const char* suffix);
// Attach child frame to a parent body, return the attached frame if success or NULL otherwise.
MJAPI mjsFrame* mjs_attachFrame(mjsBody* parent, const mjsFrame* child,
const char* prefix, const char* suffix);
// Attach child body to a parent site, return the attached body if success or NULL otherwise.
MJAPI mjsBody* mjs_attachToSite(mjsSite* parent, const mjsBody* child,
const char* prefix, const char* suffix);
// Detach body from mjSpec, remove all references and delete the body, return 0 on success.
// Delete body and descendants from mjSpec, remove all references, return 0 on success.
MJAPI int mjs_detachBody(mjSpec* s, mjsBody* b);
// Delete default class and descendants from mjSpec, remove all references, return 0 on success.
MJAPI int mjs_detachDefault(mjSpec* s, mjsDefault* d);
//---------------------------------- Tree elements -------------------------------------------------
@ -1549,6 +1543,12 @@ MJAPI mjsElement* mjs_findElement(mjSpec* s, mjtObj type, const char* name);
// Find child body by name.
MJAPI mjsBody* mjs_findChild(mjsBody* body, const char* name);
// Get parent body.
MJAPI mjsBody* mjs_getParent(mjsElement* element);
// Get parent frame.
MJAPI mjsFrame* mjs_getFrame(mjsElement* element);
// Find frame by name.
MJAPI mjsFrame* mjs_findFrame(mjSpec* s, const char* name);
@ -1556,7 +1556,7 @@ MJAPI mjsFrame* mjs_findFrame(mjSpec* s, const char* name);
MJAPI mjsDefault* mjs_getDefault(mjsElement* element);
// Find default in model by class name.
MJAPI const mjsDefault* mjs_findDefault(mjSpec* s, const char* classname);
MJAPI mjsDefault* mjs_findDefault(mjSpec* s, const char* classname);
// Get global default from model.
MJAPI mjsDefault* mjs_getSpecDefault(mjSpec* s);
@ -1628,8 +1628,8 @@ MJAPI const double* mjs_getDouble(const mjDoubleVec* source, int* size);
// Set element's default.
MJAPI void mjs_setDefault(mjsElement* element, const mjsDefault* def);
// Set element's enclosing frame.
MJAPI void mjs_setFrame(mjsElement* dest, mjsFrame* frame);
// Set element's enclosing frame, return 0 on success.
MJAPI int mjs_setFrame(mjsElement* dest, mjsFrame* frame);
// Resolve alternative orientations to quat, return error if any.
MJAPI const char* mjs_resolveOrientation(double quat[4], mjtByte degree, const char* sequence,
@ -1638,6 +1638,15 @@ MJAPI const char* mjs_resolveOrientation(double quat[4], mjtByte degree, const c
// Transform body into a frame.
MJAPI mjsFrame* mjs_bodyToFrame(mjsBody** body);
// Set user payload, overriding the existing value for the specified key if present.
MJAPI void mjs_setUserValue(mjsElement* element, const char* key, const void* data);
// Return user payload or NULL if none found.
MJAPI const void* mjs_getUserValue(mjsElement* element, const char* key);
// Delete user payload.
MJAPI void mjs_deleteUserValue(mjsElement* element, const char* key);
//---------------------------------- Element initialization ---------------------------------------
// Default spec attributes.

View File

@ -1,48 +0,0 @@
# Copyright 2021 DeepMind Technologies Limited
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# https://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
####### Expanded from @PACKAGE_INIT@ by configure_package_config_file() #######
####### Any changes to this file will be overwritten by the next CMake run ####
####### The input file was mujocoConfig.cmake.in ########
get_filename_component(PACKAGE_PREFIX_DIR "${CMAKE_CURRENT_LIST_DIR}/../../../" ABSOLUTE)
macro(set_and_check _var _file)
set(${_var} "${_file}")
if(NOT EXISTS "${_file}")
message(FATAL_ERROR "File or directory ${_file} referenced by variable ${_var} does not exist !")
endif()
endmacro()
macro(check_required_components _NAME)
foreach(comp ${${_NAME}_FIND_COMPONENTS})
if(NOT ${_NAME}_${comp}_FOUND)
if(${_NAME}_FIND_REQUIRED_${comp})
set(${_NAME}_FOUND FALSE)
endif()
endif()
endforeach()
endmacro()
####################################################################################
include(CMakeFindDependencyMacro)
find_dependency(OpenGL)
if(NOT TARGET mujoco AND NOT mujoco_BINARY_DIR)
include("${CMAKE_CURRENT_LIST_DIR}/mujocoTargets.cmake")
endif()
check_required_components(mujoco)

View File

@ -1,43 +0,0 @@
# This is a basic version file for the Config-mode of find_package().
# It is used by write_basic_package_version_file() as input file for configure_file()
# to create a version-file which can be installed along a config.cmake file.
#
# The created file sets PACKAGE_VERSION_EXACT if the current version string and
# the requested version string are exactly the same and it sets
# PACKAGE_VERSION_COMPATIBLE if the current version is >= requested version.
# The variable CVF_VERSION must be set before calling configure_file().
set(PACKAGE_VERSION "3.2.7")
if (PACKAGE_FIND_VERSION_RANGE)
# Package version must be in the requested version range
if ((PACKAGE_FIND_VERSION_RANGE_MIN STREQUAL "INCLUDE" AND PACKAGE_VERSION VERSION_LESS PACKAGE_FIND_VERSION_MIN)
OR ((PACKAGE_FIND_VERSION_RANGE_MAX STREQUAL "INCLUDE" AND PACKAGE_VERSION VERSION_GREATER PACKAGE_FIND_VERSION_MAX)
OR (PACKAGE_FIND_VERSION_RANGE_MAX STREQUAL "EXCLUDE" AND PACKAGE_VERSION VERSION_GREATER_EQUAL PACKAGE_FIND_VERSION_MAX)))
set(PACKAGE_VERSION_COMPATIBLE FALSE)
else()
set(PACKAGE_VERSION_COMPATIBLE TRUE)
endif()
else()
if(PACKAGE_VERSION VERSION_LESS PACKAGE_FIND_VERSION)
set(PACKAGE_VERSION_COMPATIBLE FALSE)
else()
set(PACKAGE_VERSION_COMPATIBLE TRUE)
if(PACKAGE_FIND_VERSION STREQUAL PACKAGE_VERSION)
set(PACKAGE_VERSION_EXACT TRUE)
endif()
endif()
endif()
# if the installed or the using project don't have CMAKE_SIZEOF_VOID_P set, ignore it:
if("${CMAKE_SIZEOF_VOID_P}" STREQUAL "" OR "8" STREQUAL "")
return()
endif()
# check that the installed version has the same 32/64bit-ness as the one which is currently searching:
if(NOT CMAKE_SIZEOF_VOID_P STREQUAL "8")
math(EXPR installedBits "8 * 8")
set(PACKAGE_VERSION "${PACKAGE_VERSION} (${installedBits}bit)")
set(PACKAGE_VERSION_UNSUITABLE TRUE)
endif()

View File

@ -1,19 +0,0 @@
#----------------------------------------------------------------
# Generated CMake target import file for configuration "Release".
#----------------------------------------------------------------
# Commands may need to know the format version.
set(CMAKE_IMPORT_FILE_VERSION 1)
# Import target "mujoco::mujoco" for configuration "Release"
set_property(TARGET mujoco::mujoco APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE)
set_target_properties(mujoco::mujoco PROPERTIES
IMPORTED_IMPLIB_RELEASE "${_IMPORT_PREFIX}/lib/mujoco.lib"
IMPORTED_LOCATION_RELEASE "${_IMPORT_PREFIX}/bin/mujoco.dll"
)
list(APPEND _cmake_import_check_targets mujoco::mujoco )
list(APPEND _cmake_import_check_files_for_mujoco::mujoco "${_IMPORT_PREFIX}/lib/mujoco.lib" "${_IMPORT_PREFIX}/bin/mujoco.dll" )
# Commands beyond this point should not need to know the version.
set(CMAKE_IMPORT_FILE_VERSION)

View File

@ -1,107 +0,0 @@
# Generated by CMake
if("${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}" LESS 2.8)
message(FATAL_ERROR "CMake >= 2.8.0 required")
endif()
if(CMAKE_VERSION VERSION_LESS "2.8.3")
message(FATAL_ERROR "CMake >= 2.8.3 required")
endif()
cmake_policy(PUSH)
cmake_policy(VERSION 2.8.3...3.28)
#----------------------------------------------------------------
# Generated CMake target import file.
#----------------------------------------------------------------
# Commands may need to know the format version.
set(CMAKE_IMPORT_FILE_VERSION 1)
# Protect against multiple inclusion, which would fail when already imported targets are added once more.
set(_cmake_targets_defined "")
set(_cmake_targets_not_defined "")
set(_cmake_expected_targets "")
foreach(_cmake_expected_target IN ITEMS mujoco::mujoco)
list(APPEND _cmake_expected_targets "${_cmake_expected_target}")
if(TARGET "${_cmake_expected_target}")
list(APPEND _cmake_targets_defined "${_cmake_expected_target}")
else()
list(APPEND _cmake_targets_not_defined "${_cmake_expected_target}")
endif()
endforeach()
unset(_cmake_expected_target)
if(_cmake_targets_defined STREQUAL _cmake_expected_targets)
unset(_cmake_targets_defined)
unset(_cmake_targets_not_defined)
unset(_cmake_expected_targets)
unset(CMAKE_IMPORT_FILE_VERSION)
cmake_policy(POP)
return()
endif()
if(NOT _cmake_targets_defined STREQUAL "")
string(REPLACE ";" ", " _cmake_targets_defined_text "${_cmake_targets_defined}")
string(REPLACE ";" ", " _cmake_targets_not_defined_text "${_cmake_targets_not_defined}")
message(FATAL_ERROR "Some (but not all) targets in this export set were already defined.\nTargets Defined: ${_cmake_targets_defined_text}\nTargets not yet defined: ${_cmake_targets_not_defined_text}\n")
endif()
unset(_cmake_targets_defined)
unset(_cmake_targets_not_defined)
unset(_cmake_expected_targets)
# Compute the installation prefix relative to this file.
get_filename_component(_IMPORT_PREFIX "${CMAKE_CURRENT_LIST_FILE}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
get_filename_component(_IMPORT_PREFIX "${_IMPORT_PREFIX}" PATH)
if(_IMPORT_PREFIX STREQUAL "/")
set(_IMPORT_PREFIX "")
endif()
# Create imported target mujoco::mujoco
add_library(mujoco::mujoco SHARED IMPORTED)
set_target_properties(mujoco::mujoco PROPERTIES
INTERFACE_COMPILE_DEFINITIONS "mjUSEPLATFORMSIMD"
INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include/"
)
# Load information for each installed configuration.
file(GLOB _cmake_config_files "${CMAKE_CURRENT_LIST_DIR}/mujocoTargets-*.cmake")
foreach(_cmake_config_file IN LISTS _cmake_config_files)
include("${_cmake_config_file}")
endforeach()
unset(_cmake_config_file)
unset(_cmake_config_files)
# Cleanup temporary variables.
set(_IMPORT_PREFIX)
# Loop over all imported files and verify that they actually exist
foreach(_cmake_target IN LISTS _cmake_import_check_targets)
if(CMAKE_VERSION VERSION_LESS "3.28"
OR NOT DEFINED _cmake_import_check_xcframework_for_${_cmake_target}
OR NOT IS_DIRECTORY "${_cmake_import_check_xcframework_for_${_cmake_target}}")
foreach(_cmake_file IN LISTS "_cmake_import_check_files_for_${_cmake_target}")
if(NOT EXISTS "${_cmake_file}")
message(FATAL_ERROR "The imported target \"${_cmake_target}\" references the file
\"${_cmake_file}\"
but this file does not exist. Possible reasons include:
* The file was deleted, renamed, or moved to another location.
* An install or uninstall procedure did not complete successfully.
* The installation package was faulty and contained
\"${CMAKE_CURRENT_LIST_FILE}\"
but not all the files it references.
")
endif()
endforeach()
endif()
unset(_cmake_file)
unset("_cmake_import_check_files_for_${_cmake_target}")
endforeach()
unset(_cmake_target)
unset(_cmake_import_check_targets)
# This file does not depend on other imported targets which have
# been exported from the same project but in a separate export set.
# Commands beyond this point should not need to know the version.
set(CMAKE_IMPORT_FILE_VERSION)
cmake_policy(POP)