Skip to content

Commit 30e15cf

Browse files
committed
first commit
1 parent 4af32d7 commit 30e15cf

33 files changed

+2761
-1
lines changed

.gitignore

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
MJDATA.TXT
2+
MUJOCO_LOG.TXT
3+
*.slxc
4+
*.autosave
5+
*.asv
6+
slprj/
7+
html/
8+
*ert_rtw/
9+
*_ert_shrlib_rtw/
10+
*_rtw/
11+
callgrind.out*
12+
*.slx.original
13+
*.zip
14+
*.tar.gz
15+
*.gz
16+
*.o
17+
references/
18+
*.exe
19+
*.out
20+
*.dylib
21+
*.dll
22+
*.so
23+
*.mexw64
24+
*.mexa64
25+
*.mexi64
26+
*.pdb
27+
BF_RESULT/
28+
temp/
29+
model_report.htmx
30+
*.pdb
31+
CP_result/
32+
BP_result/
33+
*.r2021b
34+
*.r2022a
35+
*.r2021a
36+
.vs/
37+
.vscode/
38+
win64/
39+
glnxa64/
40+
maci64/
41+
maca64/
42+
arm64/

README.md

Lines changed: 122 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1,122 @@
1-
# mujoco-simulink-blockset
1+
# Simulink Blockset for MuJoCo Simulator
2+
3+
This repository provides a Simulink® C-MEX S-Function block interface to [MuJoCo™ physics engine](https://mujoco.org/).
4+
5+
[![View <File Exchange Title> on File Exchange](https://www.mathworks.com/matlabcentral/images/matlab-file-exchange.svg)](https://www.mathworks.com/matlabcentral/fileexchange/####-file-exchange-title)
6+
7+
Useful for,
8+
1. Robot simulation (mobile, biomimetic, grippers, robotic arm)
9+
2. Development of autonomous algorithms using classical or machine learning based approaches
10+
3. Camera (RGB, Depth) rendering
11+
12+
## Installation Instructions
13+
14+
### MathWorks&reg; Products (https://www.mathworks.com)
15+
16+
- MATLAB&reg; (required)
17+
- Simulink&reg; (required)
18+
- Computer Vision Toolbox&trade; (optional)
19+
- Robotics System Toolbox&trade; (optional)
20+
- Control System Toolbox&trade; (optional)
21+
- Simulink&reg; Coder&trade; (optional)
22+
23+
MATLAB R2022b or newer recommended. Install MATLAB with the above products and then proceed to setting up MuJoCo blocks.
24+
25+
*Note - You may need to rebuild the S-Function if you are using an older release of MATLAB*.
26+
27+
### Simulink Blockset for MuJoCo
28+
29+
#### Windows&reg;:
30+
31+
- Download the latest release of this repository
32+
- Open MATLAB R2022b. In case you are using a older MATLAB release, please follow the build instructions below to rebuild for a particular MATLAB release
33+
- Run install.m in MATLAB command window. MuJoCo and GLFW libraries will be downloaded and added to MATLAB Path.
34+
35+
#### Ubuntu&reg;:
36+
37+
- Download the latest release of this repository
38+
- Download and install GLFW library from Ubuntu terminal
39+
40+
`sudo apt update && sudo apt install libglfw3 libglfw3-dev`
41+
- Open MATLAB R2022b. In case you are using a older MATLAB release, please follow the build instructions below to rebuild for a particular MATLAB release
42+
- Run install.m in MATLAB command window. MuJoCo library will be downloaded and added to MATLAB Path.
43+
44+
## Usage
45+
Open examples/gettingStarted.slx model and click run
46+
47+
If the installation is successful, you should see a pendulum model running in a separate window and camera stream displayed by Video Viewer block (Computer Vision Toolbox)
48+
49+
### Blocks
50+
51+
![](mjLib.png){height=250px}
52+
53+
MuJoCo Plant block steps MuJoCo engine, renders visualization window & camera, sets actuator data and outputs sensor readings
54+
55+
It takes an XML (MJCF) as the main block parameter. It auto detects the inputs, sensors, cameras from XML and sets the ports, sample time and other internal configuration.
56+
57+
Inputs can either be a Simulink Bus or vector.
58+
59+
Sensors are output as a Simulink Bus.
60+
61+
RGB and Depth buffers from camera are output as vectors. These can be decoded to Simulink image/matrix using the RGB and Depth Parser blocks.
62+
63+
![](getting_started_clip1.mp4 "Block Usage")
64+
![](getting_started_clip2.mp4 "Visualization")
65+
66+
## Build Instructions (optional)
67+
68+
Steps for building/rebuilding the C-MEX S-Function code. These instructions are only required if you are cloning the repository instead of downloading the release.
69+
70+
### Windows:
71+
72+
- Install one of the following C++ Compiler
73+
- Microsoft&reg; Visual Studio&reg; 2022 or higher (recommended)
74+
- (or) [MinGW (GCC 12.2.0 or higher)](https://community.chocolatey.org/packages/mingw)
75+
- Clone this repository
76+
- Launch MATLAB and open the repository folder
77+
- `>> install`
78+
- Open tools/
79+
- Open setupBuild.m. In case you are using MinGW compiler, edit the file and set selectedCompilerWin to "MINGW".
80+
- `>> setupBuild`
81+
- `>> mex -setup c++`
82+
- `>> build`
83+
84+
### Ubuntu
85+
86+
- Install the tools required for compiling the S-Function
87+
88+
`$ sudo apt update && sudo apt install build-essential git libglfw3 libglfw3-dev `
89+
- Clone this repository
90+
91+
`$ git clone <this_repository.git>`
92+
- Launch MATLAB and open the repository folder. Run the install.m script.
93+
- `>> install`
94+
- Open tools/ and run the following commands in MATLAB command Windows
95+
- `>> setupBuild`
96+
- `>> mex -setup c++`
97+
- `>> build`
98+
99+
100+
## License
101+
102+
The license is available in the license.txt file within this repository.
103+
104+
## Acknowledgements
105+
Cite this work as,
106+
107+
Manoj Velmurugan. Simulink Blockset for MuJoCo Simulator (https://github.com/mathworks-robotics/mujoco-simulink-blockset), GitHub. Retrieved March 27, 2023.
108+
109+
110+
Refer to [MuJoCo repository](https://github.com/deepmind/mujoco) for guidelines on citing MuJoCo physics engine.
111+
112+
The sample codes and API documentation provided for [MuJoCo](https://mujoco.readthedocs.io/en/latest/overview.html) and [GLFW](https://www.glfw.org/documentation) were used as reference material during development.
113+
114+
MuJoCo and GLFW libraries are dynamically linked against the S-Function and are required for running this blockset.
115+
116+
UR5e MJCF XML from [MuJoCo Menagerie](https://github.com/deepmind/mujoco_menagerie/tree/main/universal_robots_ur5e) was used for creating demo videos.
117+
118+
## Community Support
119+
120+
You can post your queries on the [MATLAB&reg; Central&trade; File Exchange](https://www.mathworks.com/matlabcentral/fileexchange/####-file-exchange-title) page.
121+
122+
Copyright 2023 The MathWorks, Inc.

SECURITY.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
# Reporting Security Vulnerabilities
2+
3+
If you believe you have discovered a security vulnerability, please report it to
4+
[security@mathworks.com](mailto:security@mathworks.com). Please see
5+
[MathWorks Vulnerability Disclosure Policy for Security Researchers](https://www.mathworks.com/company/aboutus/policies_statements/vulnerability-disclosure-policy.html)
6+
for additional information.

blocks/.gitignore

Whitespace-only changes.

blocks/dummy.xml

Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
<mujoco model="arm_with_cam">
2+
<option timestep="0.005" iterations="50" solver="Newton" tolerance="1e-10"/>
3+
<visual>
4+
<rgba haze=".3 .3 .3 1"/>
5+
</visual>
6+
<asset>
7+
<texture name="texplane" type="2d" builtin="checker" rgb1=".25 .25 .25" rgb2=".3 .3 .3" width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>
8+
<material name="matplane" reflectance="0.3" texture="texplane" texrepeat="1 1" texuniform="true"/>
9+
</asset>
10+
11+
<sensor>
12+
<framequat name="imu" objtype="body" objname="armBody" />
13+
</sensor>
14+
15+
<worldbody>
16+
<geom name="floor" pos="0 0 0" size="0 0 1" type="plane" material="matplane"/>
17+
<light directional="true" diffuse=".7 .7 .8" specular=".2 .2 .2" pos="0 0 1" dir="0 0 -1"/>
18+
<camera name="PerspectiveCamera" mode="fixed" pos="0 0 6" euler="0 -20 90"/>
19+
20+
<body pos="0 0 0">
21+
<geom name="base1" type="box" size="0.1 0.1 1" pos="0 0 1" rgba="0.2 0.6 0.5 1"/>
22+
23+
<body name="armBody" pos="0.25 0 2">
24+
<geom name="arm" type="box" size="0.1 0.8 0.1" pos="0 0.8 0" rgba="0.2 0.6 0.5 1"/>
25+
<!-- <joint name="joint" type="hinge" pos="0 0 0" axis="1 0 0" frictionloss="50"/> -->
26+
<joint name="joint" type="hinge" pos="0 0 0" axis="1 0 0" frictionloss="0"/>
27+
<camera name="camera" mode="fixed" pos="0.2 0 0" euler="0 -90 0"/>
28+
<geom name="cameraGeom" type="box" pos="0.15 0 0" size="0.05 0.1 0.1" rgba="0.4 0.2 0.6 1"/>
29+
</body>
30+
</body>
31+
32+
<body pos="0 0 0">
33+
<geom name="red box" type="box" size="0.5 0.5 0.5" pos="4 0 1" rgba="1 0 0 1"/>
34+
<freejoint/>
35+
</body>
36+
37+
<body pos="0 0 0">
38+
<geom name="blue box" type="box" size="0.5 0.5 0.5" pos="4 0 1.5" rgba="0 1 0 1"/>
39+
<freejoint/>
40+
</body>
41+
42+
<body pos="0 0 0">
43+
<geom name="green box" type="box" size="0.5 0.5 0.5" pos="4 0 2" rgba="0 0 1 1"/>
44+
<freejoint/>
45+
</body>
46+
47+
48+
</worldbody>
49+
50+
<actuator>
51+
<motor name="armMotor" joint="joint" gear="100" />
52+
</actuator>
53+
54+
<!-- Copyright 2022-2023 The MathWorks, Inc. -->
55+
</mujoco>

blocks/mjLib.slx

57.3 KB
Binary file not shown.

blocks/mj_busExist.m

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
function x = mj_busExist(busName)
2+
% Copyright 2022-2023 The MathWorks, Inc.
3+
x=evalin('base', strcat("exist('", busName, "', 'var')"));
4+
end

blocks/mj_initbus.m

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
function [a,b,c,d,e] = mj_initbus(xmlPath)
2+
% Copyright 2022-2023 The MathWorks, Inc.
3+
% Lets just be on safe side and run mj_initbus_mex in a separate
4+
% process. It calls glfw functions which work best in a main thread of
5+
% a separate process.
6+
persistent mh
7+
if ~(isa(mh,'matlab.mex.MexHost') && isvalid(mh))
8+
mh = mexhost;
9+
end
10+
[a,b,c,d, e] = feval(mh, 'mj_initbus_mex', xmlPath);
11+
% [a,b,c,d,e] = mj_initbus_mex(xmlPath);
12+
end

blocks/mj_maskinit.m

Lines changed: 139 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,139 @@
1+
% Copyright 2022-2023 The MathWorks, Inc.
2+
mjBlk = gcb;
3+
mo = get_param(mjBlk,'MaskObject');
4+
%% Sensor Bus Config
5+
blankBusPath = [mjBlk, '/sensorToBus/blankSensorBus'];
6+
sensorToBusPath = [mjBlk, '/sensorToBus'];
7+
sensorOut1Path = [mjBlk, '/sensor'];
8+
portIndex = 1;
9+
try
10+
sensorFieldnames = fieldnames(Simulink.Bus.createMATLABStruct(sensorBus));
11+
%fails when it is an empty bus TODO. remove try catch
12+
catch
13+
sensorFieldnames = [];
14+
end
15+
16+
if isempty(sensorFieldnames)
17+
mo.getDialogControl('sensorBusText').Prompt = ['Sensor Bus Type: ', 'NA'];
18+
set_param(sensorToBusPath, 'Commented', 'through');
19+
replacer(mjBlk, 'sensor', 'simulink/Sinks/Terminator')
20+
else
21+
mo.getDialogControl('sensorBusText').Prompt = ['Sensor Bus Type: ', sensorBus];
22+
set_param(sensorToBusPath, 'Commented', 'off');
23+
outportName = 'sensor';
24+
replacer(mjBlk, outportName, 'simulink/Sinks/Out1');
25+
set_param([mjBlk, '/', outportName], "Port", num2str(portIndex));
26+
portIndex = portIndex+1;
27+
28+
set_param(blankBusPath, 'OutDataTypeStr', ['Bus: ', sensorBus]);
29+
set_param([sensorToBusPath '/parser'], 'OutputBusName', sensorBus);
30+
end
31+
32+
%% Control Bus Config
33+
controlInportPath = [mjBlk, '/', 'u'];
34+
uToVectorPath = [mjBlk, '/', 'uToVector'];
35+
uPortExpander = [mjBlk, '/uPortExpander'];
36+
try
37+
controlFieldnames = fieldnames(Simulink.Bus.createMATLABStruct(controlBus));
38+
%fails when controlBus is an empty bus TODO. remove try catch
39+
catch
40+
controlFieldnames = [];
41+
end
42+
43+
% Remove inport for passive simulation case
44+
if isempty(controlFieldnames)
45+
replacer(mjBlk, 'u', 'simulink/Sources/Ground');
46+
set_param(uToVectorPath, 'Commented', 'through');
47+
mo.getDialogControl('controlBusText').Prompt = 'Control Vector Type: NA';
48+
set_param(uPortExpander, 'Commented', 'through');
49+
else
50+
set_param(uPortExpander, 'Commented', 'off');
51+
replacer(mjBlk, 'u', 'simulink/Sources/In1');
52+
% Set bus or vector
53+
if strcmp(get_param(mjBlk, 'controlInterfaceType'), 'Bus')
54+
set_param(controlInportPath, 'OutDataTypeStr', ['Bus: ', controlBus]);
55+
set_param(uToVectorPath, 'Commented', 'off');
56+
mo.getDialogControl('controlBusText').Prompt = ['Control Bus Type: ', controlBus];
57+
set_param(controlInportPath, 'PortDimensions', '-1')
58+
elseif strcmp(get_param(mjBlk, 'controlInterfaceType'), 'Vector')
59+
set_param(controlInportPath, 'OutDataTypeStr', 'Inherit: auto');
60+
set_param(uToVectorPath, 'Commented', 'through');
61+
mo.getDialogControl('controlBusText').Prompt = ['Control Vector Type: [', strjoin(controlFieldnames, ', '), ']'];
62+
inputDim = [length(controlFieldnames) 1];
63+
set_param(controlInportPath, 'PortDimensions', ['[' num2str(inputDim), ']']);
64+
end
65+
end
66+
67+
%% RGB
68+
69+
% blankBusPath = [mjBlk, '/rgbToBus/blankBus'];
70+
% rgbToBusPath = [mjBlk, '/rgbToBus'];
71+
rgbOut1Path = [mjBlk, '/rgb'];
72+
try
73+
rgbFieldnames = fieldnames(Simulink.Bus.createMATLABStruct(rgbBus));
74+
%fails when it is an empty bus TODO. remove try catch
75+
mo.getDialogControl('rgbBusText').Prompt = ['RGB Bus Type: ', rgbBus];
76+
catch
77+
rgbFieldnames = [];
78+
mo.getDialogControl('rgbBusText').Prompt = ['RGB Bus Type: ', 'NA'];
79+
end
80+
81+
if isempty(rgbFieldnames)
82+
replacer(mjBlk, 'rgb', 'simulink/Sinks/Terminator')
83+
else
84+
outportName = 'rgb';
85+
replacer(mjBlk, outportName, 'simulink/Sinks/Out1');
86+
set_param([mjBlk, '/', outportName], "Port", num2str(portIndex));
87+
portIndex = portIndex+1;
88+
end
89+
90+
%% Depth
91+
mo.getDialogControl('rgbBusText').Prompt = ['RGB Bus Type: ', rgbBus];
92+
depthOut1Path = [mjBlk, '/depth'];
93+
depthConverterPath = [mjBlk, '/OpenGL Depth conversion'];
94+
try
95+
depthFieldnames = fieldnames(Simulink.Bus.createMATLABStruct(depthBus));
96+
%fails when it is an empty bus TODO. remove try catch
97+
mo.getDialogControl('depthBusText').Prompt = ['Depth Bus Type: ', depthBus];
98+
catch
99+
depthFieldnames = [];
100+
mo.getDialogControl('depthBusText').Prompt = ['Depth Bus Type: ', 'NA'];
101+
end
102+
depthOutputOption = strcmp(get_param(mjBlk, 'depthOutOption'), 'on');
103+
104+
if isempty(depthFieldnames) || ~depthOutputOption
105+
set_param(depthConverterPath, 'Commented', 'on');
106+
replacer(mjBlk, 'depth', 'simulink/Sinks/Terminator')
107+
else
108+
set_param(depthConverterPath, 'Commented', 'off');
109+
outportName = 'depth';
110+
replacer(mjBlk, 'depth', 'simulink/Sinks/Out1');
111+
set_param([mjBlk, '/', outportName], "Port", num2str(portIndex));
112+
portIndex = portIndex+1;
113+
end
114+
115+
[znear, zfar] = mj_depth_near_far(xmlFile);
116+
set_param(mjBlk, 'znear', num2str(znear));
117+
set_param(mjBlk, 'zfar', num2str(zfar));
118+
119+
%% Sample Time
120+
sampleTime = mj_sampletime(xmlFile);
121+
set_param(mjBlk, 'sampleTime', num2str(sampleTime));
122+
123+
mo.getDialogControl('sampleTimeText').Prompt = ['Sample Time: ', num2str(sampleTime)];
124+
125+
function replacer(blk, oldname, newtype)
126+
oldpath = [blk, '/', oldname];
127+
newTypeWithoutLib = strsplit(newtype, '/');
128+
newTypeWithoutLib = newTypeWithoutLib{end};
129+
if strcmp(newTypeWithoutLib, 'In1')
130+
newTypeWithoutLib = 'Inport';
131+
elseif strcmp(newTypeWithoutLib, 'Out1')
132+
newTypeWithoutLib = 'Outport';
133+
end
134+
if ~strcmp(get_param(oldpath, 'BlockType'), newTypeWithoutLib)
135+
position = get_param(oldpath, 'Position');
136+
delete_block(oldpath);
137+
add_block(newtype, oldpath, 'Position', position);
138+
end
139+
end

0 commit comments

Comments
 (0)