simulate.cc 91 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092209320942095209620972098209921002101210221032104210521062107210821092110211121122113211421152116211721182119212021212122212321242125212621272128212921302131213221332134213521362137213821392140214121422143214421452146214721482149215021512152215321542155215621572158215921602161216221632164216521662167216821692170217121722173217421752176217721782179218021812182218321842185218621872188218921902191219221932194219521962197219821992200220122022203220422052206220722082209221022112212221322142215221622172218221922202221222222232224222522262227222822292230223122322233223422352236223722382239224022412242224322442245224622472248224922502251225222532254225522562257225822592260226122622263226422652266226722682269227022712272227322742275227622772278227922802281228222832284228522862287228822892290229122922293229422952296229722982299230023012302230323042305230623072308230923102311231223132314231523162317231823192320232123222323232423252326232723282329233023312332233323342335233623372338233923402341234223432344234523462347234823492350235123522353235423552356235723582359236023612362236323642365236623672368236923702371237223732374237523762377237823792380238123822383238423852386238723882389239023912392239323942395239623972398239924002401240224032404240524062407240824092410241124122413241424152416241724182419242024212422242324242425242624272428242924302431243224332434243524362437243824392440244124422443244424452446244724482449245024512452245324542455245624572458245924602461246224632464246524662467246824692470247124722473247424752476247724782479248024812482248324842485248624872488248924902491249224932494249524962497249824992500250125022503250425052506250725082509251025112512251325142515251625172518251925202521252225232524252525262527252825292530253125322533253425352536253725382539254025412542254325442545254625472548254925502551255225532554255525562557255825592560256125622563256425652566256725682569257025712572257325742575257625772578257925802581258225832584258525862587258825892590259125922593259425952596259725982599260026012602260326042605260626072608260926102611261226132614261526162617261826192620262126222623262426252626262726282629263026312632263326342635263626372638263926402641264226432644264526462647264826492650265126522653265426552656265726582659266026612662266326642665266626672668266926702671267226732674267526762677267826792680268126822683268426852686268726882689269026912692269326942695269626972698269927002701270227032704270527062707270827092710271127122713271427152716271727182719272027212722272327242725272627272728272927302731273227332734273527362737273827392740274127422743274427452746274727482749275027512752275327542755275627572758275927602761276227632764276527662767276827692770277127722773277427752776277727782779278027812782278327842785278627872788278927902791279227932794279527962797279827992800280128022803280428052806280728082809281028112812
  1. // Copyright 2021 DeepMind Technologies Limited
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #include "simulate.h"
  15. #include <algorithm>
  16. #include <atomic>
  17. #include <chrono>
  18. #include <climits>
  19. #include <cstdio>
  20. #include <cstring>
  21. #include <memory>
  22. #include <optional>
  23. #include <ratio>
  24. #include <string>
  25. #include <type_traits>
  26. #include <utility>
  27. #include "lodepng.h"
  28. #include <mujoco/mjdata.h>
  29. #include <mujoco/mjui.h>
  30. #include <mujoco/mjvisualize.h>
  31. #include <mujoco/mjxmacro.h>
  32. #include <mujoco/mujoco.h>
  33. #include "platform_ui_adapter.h"
  34. #include "array_safety.h"
  35. // When launched via an App Bundle on macOS, the working directory is the path to the App Bundle's
  36. // resource directory. This causes files to be saved into the bundle, which is not the desired
  37. // behavior. Instead, we open a save dialog box to ask the user where to put the file.
  38. // Since the dialog box logic needs to be written in Objective-C, we separate it into a different
  39. // source file.
  40. #ifdef __APPLE__
  41. std::string GetSavePath(const char* filename);
  42. #else
  43. static std::string GetSavePath(const char* filename) {
  44. return filename;
  45. }
  46. #endif
  47. namespace {
  48. namespace mj = ::mujoco;
  49. namespace mju = ::mujoco::sample_util;
  50. using Seconds = std::chrono::duration<double>;
  51. using Milliseconds = std::chrono::duration<double, std::milli>;
  52. template <typename T>
  53. inline bool IsDifferent(const T& a, const T& b) {
  54. if constexpr (std::is_array_v<T>) {
  55. static_assert(std::rank_v<T> == 1);
  56. for (int i = 0; i < std::extent_v<T>; ++i) {
  57. if (a[i] != b[i]) {
  58. return true;
  59. }
  60. }
  61. return false;
  62. } else {
  63. return a != b;
  64. }
  65. }
  66. template <typename T>
  67. inline void CopyScalar(T& dst, const T& src) {
  68. dst = src;
  69. }
  70. template <typename T, int N>
  71. inline void CopyArray(T (&dst)[N], const T (&src)[N]) {
  72. for (int i = 0; i < N; ++i) {
  73. dst[i] = src[i];
  74. }
  75. }
  76. template <typename T>
  77. inline void Copy(T& dst, const T& src) {
  78. if constexpr (std::is_array_v<T>) {
  79. CopyArray(dst, src);
  80. } else {
  81. CopyScalar(dst, src);
  82. }
  83. }
  84. //------------------------------------------- global -----------------------------------------------
  85. const double zoom_increment = 0.02; // ratio of one click-wheel zoom increment to vertical extent
  86. // section ids
  87. enum {
  88. // left ui
  89. SECT_FILE = 0,
  90. SECT_OPTION,
  91. SECT_SIMULATION,
  92. SECT_WATCH,
  93. SECT_PHYSICS,
  94. SECT_RENDERING,
  95. SECT_VISUALIZATION,
  96. SECT_GROUP,
  97. NSECT0,
  98. // right ui
  99. SECT_JOINT = 0,
  100. SECT_CONTROL,
  101. NSECT1
  102. };
  103. // file section of UI
  104. const mjuiDef defFile[] = {
  105. {mjITEM_SECTION, "File", mjPRESERVE, nullptr, "AF"},
  106. {mjITEM_BUTTON, "Save xml", 2, nullptr, ""},
  107. {mjITEM_BUTTON, "Save mjb", 2, nullptr, ""},
  108. {mjITEM_BUTTON, "Print model", 2, nullptr, "CM"},
  109. {mjITEM_BUTTON, "Print data", 2, nullptr, "CD"},
  110. {mjITEM_BUTTON, "Quit", 1, nullptr, "CQ"},
  111. {mjITEM_BUTTON, "Screenshot", 2, nullptr, "CP"},
  112. {mjITEM_END}
  113. };
  114. // help strings
  115. const char help_content[] =
  116. "Space\n"
  117. "+ -\n"
  118. "Left / Right arrow\n"
  119. "Tab / Shift-Tab\n"
  120. "[ ]\n"
  121. "Esc\n"
  122. "Double-click\n"
  123. "Page Up\n"
  124. "Right double-click\n"
  125. "Ctrl Right double-click\n"
  126. "Scroll, middle drag\n"
  127. "Left drag\n"
  128. "[Shift] right drag\n"
  129. "Ctrl [Shift] drag\n"
  130. "Ctrl [Shift] right drag\n"
  131. "F1\n"
  132. "F2\n"
  133. "F3\n"
  134. "F4\n"
  135. "F5\n"
  136. "UI right-button hold\n"
  137. "UI title double-click";
  138. const char help_title[] =
  139. "Play / Pause\n"
  140. "Speed Up / Down\n"
  141. "Step Back / Forward\n"
  142. "Toggle Left / Right UI\n"
  143. "Cycle cameras\n"
  144. "Free camera\n"
  145. "Select\n"
  146. "Select parent\n"
  147. "Center camera\n"
  148. "Tracking camera\n"
  149. "Zoom\n"
  150. "View Orbit\n"
  151. "View Pan\n"
  152. "Object Rotate\n"
  153. "Object Translate\n"
  154. "Help\n"
  155. "Info\n"
  156. "Profiler\n"
  157. "Sensors\n"
  158. "Full screen\n"
  159. "Show UI shortcuts\n"
  160. "Expand/collapse all";
  161. //-------------------------------- profiler, sensor, info, watch -----------------------------------
  162. // number of lines in the Constraint ("Counts") and Cost ("Convergence") figures
  163. static constexpr int kConstraintNum = 5;
  164. static constexpr int kCostNum = 3;
  165. // init profiler figures
  166. void InitializeProfiler(mj::Simulate* sim) {
  167. // set figures to default
  168. mjv_defaultFigure(&sim->figconstraint);
  169. mjv_defaultFigure(&sim->figcost);
  170. mjv_defaultFigure(&sim->figtimer);
  171. mjv_defaultFigure(&sim->figsize);
  172. // titles
  173. mju::strcpy_arr(sim->figconstraint.title, "Counts");
  174. mju::strcpy_arr(sim->figcost.title, "Convergence (log 10)");
  175. mju::strcpy_arr(sim->figsize.title, "Dimensions");
  176. mju::strcpy_arr(sim->figtimer.title, "CPU time (msec)");
  177. // x-labels
  178. mju::strcpy_arr(sim->figconstraint.xlabel, "Solver iteration");
  179. mju::strcpy_arr(sim->figcost.xlabel, "Solver iteration");
  180. mju::strcpy_arr(sim->figsize.xlabel, "Video frame");
  181. mju::strcpy_arr(sim->figtimer.xlabel, "Video frame");
  182. // y-tick number formats
  183. mju::strcpy_arr(sim->figconstraint.yformat, "%.0f");
  184. mju::strcpy_arr(sim->figcost.yformat, "%.1f");
  185. mju::strcpy_arr(sim->figsize.yformat, "%.0f");
  186. mju::strcpy_arr(sim->figtimer.yformat, "%.2f");
  187. // colors
  188. sim->figconstraint.figurergba[0] = 0.1f;
  189. sim->figcost.figurergba[2] = 0.2f;
  190. sim->figsize.figurergba[0] = 0.1f;
  191. sim->figtimer.figurergba[2] = 0.2f;
  192. sim->figconstraint.figurergba[3] = 0.5f;
  193. sim->figcost.figurergba[3] = 0.5f;
  194. sim->figsize.figurergba[3] = 0.5f;
  195. sim->figtimer.figurergba[3] = 0.5f;
  196. // repeat line colors for constraint and cost figures
  197. mjvFigure* fig = &sim->figcost;
  198. for (int i=kCostNum; i<mjMAXLINE; i++) {
  199. fig->linergb[i][0] = fig->linergb[i - kCostNum][0];
  200. fig->linergb[i][1] = fig->linergb[i - kCostNum][1];
  201. fig->linergb[i][2] = fig->linergb[i - kCostNum][2];
  202. }
  203. fig = &sim->figconstraint;
  204. for (int i=kConstraintNum; i<mjMAXLINE; i++) {
  205. fig->linergb[i][0] = fig->linergb[i - kConstraintNum][0];
  206. fig->linergb[i][1] = fig->linergb[i - kConstraintNum][1];
  207. fig->linergb[i][2] = fig->linergb[i - kConstraintNum][2];
  208. }
  209. // legends
  210. mju::strcpy_arr(sim->figconstraint.linename[0], "total");
  211. mju::strcpy_arr(sim->figconstraint.linename[1], "active");
  212. mju::strcpy_arr(sim->figconstraint.linename[2], "changed");
  213. mju::strcpy_arr(sim->figconstraint.linename[3], "evals");
  214. mju::strcpy_arr(sim->figconstraint.linename[4], "updates");
  215. mju::strcpy_arr(sim->figcost.linename[0], "improvement");
  216. mju::strcpy_arr(sim->figcost.linename[1], "gradient");
  217. mju::strcpy_arr(sim->figcost.linename[2], "lineslope");
  218. mju::strcpy_arr(sim->figsize.linename[0], "dof");
  219. mju::strcpy_arr(sim->figsize.linename[1], "body");
  220. mju::strcpy_arr(sim->figsize.linename[2], "constraint");
  221. mju::strcpy_arr(sim->figsize.linename[3], "sqrt(nnz)");
  222. mju::strcpy_arr(sim->figsize.linename[4], "contact");
  223. mju::strcpy_arr(sim->figsize.linename[5], "iteration");
  224. mju::strcpy_arr(sim->figtimer.linename[0], "total");
  225. mju::strcpy_arr(sim->figtimer.linename[1], "collision");
  226. mju::strcpy_arr(sim->figtimer.linename[2], "prepare");
  227. mju::strcpy_arr(sim->figtimer.linename[3], "solve");
  228. mju::strcpy_arr(sim->figtimer.linename[4], "other");
  229. // grid sizes
  230. sim->figconstraint.gridsize[0] = 5;
  231. sim->figconstraint.gridsize[1] = 5;
  232. sim->figcost.gridsize[0] = 5;
  233. sim->figcost.gridsize[1] = 5;
  234. sim->figsize.gridsize[0] = 3;
  235. sim->figsize.gridsize[1] = 5;
  236. sim->figtimer.gridsize[0] = 3;
  237. sim->figtimer.gridsize[1] = 5;
  238. // minimum ranges
  239. sim->figconstraint.range[0][0] = 0;
  240. sim->figconstraint.range[0][1] = 20;
  241. sim->figconstraint.range[1][0] = 0;
  242. sim->figconstraint.range[1][1] = 80;
  243. sim->figcost.range[0][0] = 0;
  244. sim->figcost.range[0][1] = 20;
  245. sim->figcost.range[1][0] = -15;
  246. sim->figcost.range[1][1] = 5;
  247. sim->figsize.range[0][0] = -200;
  248. sim->figsize.range[0][1] = 0;
  249. sim->figsize.range[1][0] = 0;
  250. sim->figsize.range[1][1] = 100;
  251. sim->figtimer.range[0][0] = -200;
  252. sim->figtimer.range[0][1] = 0;
  253. sim->figtimer.range[1][0] = 0;
  254. sim->figtimer.range[1][1] = 0.4f;
  255. // init x axis on history figures (do not show yet)
  256. for (int n=0; n<6; n++) {
  257. for (int i=0; i<mjMAXLINEPNT; i++) {
  258. sim->figtimer.linedata[n][2*i] = -i;
  259. sim->figsize.linedata[n][2*i] = -i;
  260. }
  261. }
  262. }
  263. // update profiler figures
  264. void UpdateProfiler(mj::Simulate* sim, const mjModel* m, const mjData* d) {
  265. // reset lines in Constraint and Cost figures
  266. memset(sim->figconstraint.linepnt, 0, mjMAXLINE*sizeof(int));
  267. memset(sim->figcost.linepnt, 0, mjMAXLINE*sizeof(int));
  268. // number of islands that have diagnostics
  269. int nisland = mjMIN(d->solver_nisland, mjNISLAND);
  270. // iterate over islands
  271. for (int k=0; k < nisland; k++) {
  272. // ==== update Constraint ("Counts") figure
  273. // number of points to plot, starting line
  274. int npoints = mjMIN(mjMIN(d->solver_niter[k], mjNSOLVER), mjMAXLINEPNT);
  275. int start = kConstraintNum * k;
  276. sim->figconstraint.linepnt[start + 0] = npoints;
  277. for (int i=1; i < kConstraintNum; i++) {
  278. sim->figconstraint.linepnt[start + i] = npoints;
  279. }
  280. if (m->opt.solver == mjSOL_PGS) {
  281. sim->figconstraint.linepnt[start + 3] = 0;
  282. sim->figconstraint.linepnt[start + 4] = 0;
  283. }
  284. if (m->opt.solver == mjSOL_CG) {
  285. sim->figconstraint.linepnt[start + 4] = 0;
  286. }
  287. for (int i=0; i<npoints; i++) {
  288. // x
  289. sim->figconstraint.linedata[start + 0][2*i] = i;
  290. sim->figconstraint.linedata[start + 1][2*i] = i;
  291. sim->figconstraint.linedata[start + 2][2*i] = i;
  292. sim->figconstraint.linedata[start + 3][2*i] = i;
  293. sim->figconstraint.linedata[start + 4][2*i] = i;
  294. // y
  295. int nefc = nisland == 1 ? d->nefc : d->island_efcnum[k];
  296. sim->figconstraint.linedata[start + 0][2*i+1] = nefc;
  297. const mjSolverStat* stat = d->solver + k*mjNSOLVER + i;
  298. sim->figconstraint.linedata[start + 1][2*i+1] = stat->nactive;
  299. sim->figconstraint.linedata[start + 2][2*i+1] = stat->nchange;
  300. sim->figconstraint.linedata[start + 3][2*i+1] = stat->neval;
  301. sim->figconstraint.linedata[start + 4][2*i+1] = stat->nupdate;
  302. }
  303. // update cost figure
  304. start = kCostNum * k;
  305. sim->figcost.linepnt[start + 0] = npoints;
  306. for (int i=1; i<kCostNum; i++) {
  307. sim->figcost.linepnt[start + i] = npoints;
  308. }
  309. if (m->opt.solver==mjSOL_PGS) {
  310. sim->figcost.linepnt[start + 1] = 0;
  311. sim->figcost.linepnt[start + 2] = 0;
  312. }
  313. for (int i=0; i<sim->figcost.linepnt[0]; i++) {
  314. // x
  315. sim->figcost.linedata[start + 0][2*i] = i;
  316. sim->figcost.linedata[start + 1][2*i] = i;
  317. sim->figcost.linedata[start + 2][2*i] = i;
  318. // y
  319. const mjSolverStat* stat = d->solver + k*mjNSOLVER + i;
  320. sim->figcost.linedata[start + 0][2*i + 1] =
  321. mju_log10(mju_max(mjMINVAL, stat->improvement));
  322. sim->figcost.linedata[start + 1][2*i + 1] =
  323. mju_log10(mju_max(mjMINVAL, stat->gradient));
  324. sim->figcost.linedata[start + 2][2*i + 1] =
  325. mju_log10(mju_max(mjMINVAL, stat->lineslope));
  326. }
  327. }
  328. // get timers: total, collision, prepare, solve, other
  329. mjtNum total = d->timer[mjTIMER_STEP].duration;
  330. int number = d->timer[mjTIMER_STEP].number;
  331. if (!number) {
  332. total = d->timer[mjTIMER_FORWARD].duration;
  333. number = d->timer[mjTIMER_FORWARD].number;
  334. }
  335. if (number) { // skip update if no measurements
  336. float tdata[5] = {
  337. static_cast<float>(total/number),
  338. static_cast<float>(d->timer[mjTIMER_POS_COLLISION].duration/number),
  339. static_cast<float>(d->timer[mjTIMER_POS_MAKE].duration/number) +
  340. static_cast<float>(d->timer[mjTIMER_POS_PROJECT].duration/number),
  341. static_cast<float>(d->timer[mjTIMER_CONSTRAINT].duration/number),
  342. 0
  343. };
  344. tdata[4] = tdata[0] - tdata[1] - tdata[2] - tdata[3];
  345. // update figtimer
  346. int pnt = mjMIN(201, sim->figtimer.linepnt[0]+1);
  347. for (int n=0; n<5; n++) {
  348. // shift data
  349. for (int i=pnt-1; i>0; i--) {
  350. sim->figtimer.linedata[n][2*i+1] = sim->figtimer.linedata[n][2*i-1];
  351. }
  352. // assign new
  353. sim->figtimer.linepnt[n] = pnt;
  354. sim->figtimer.linedata[n][1] = tdata[n];
  355. }
  356. }
  357. // get total number of iterations and nonzeros
  358. mjtNum sqrt_nnz = 0;
  359. int solver_niter = 0;
  360. for (int island=0; island < nisland; island++) {
  361. sqrt_nnz += mju_sqrt(d->solver_nnz[island]);
  362. solver_niter += d->solver_niter[island];
  363. }
  364. // get sizes: nv, nbody, nefc, sqrt(nnz), ncont, iter
  365. float sdata[6] = {
  366. static_cast<float>(m->nv),
  367. static_cast<float>(m->nbody),
  368. static_cast<float>(d->nefc),
  369. static_cast<float>(sqrt_nnz),
  370. static_cast<float>(d->ncon),
  371. static_cast<float>(solver_niter)
  372. };
  373. // update figsize
  374. int pnt = mjMIN(201, sim->figsize.linepnt[0]+1);
  375. for (int n=0; n<6; n++) {
  376. // shift data
  377. for (int i=pnt-1; i>0; i--) {
  378. sim->figsize.linedata[n][2*i+1] = sim->figsize.linedata[n][2*i-1];
  379. }
  380. // assign new
  381. sim->figsize.linepnt[n] = pnt;
  382. sim->figsize.linedata[n][1] = sdata[n];
  383. }
  384. }
  385. // show profiler figures
  386. void ShowProfiler(mj::Simulate* sim, mjrRect rect) {
  387. mjrRect viewport = {
  388. rect.left + rect.width - rect.width/4,
  389. rect.bottom,
  390. rect.width/4,
  391. rect.height/4
  392. };
  393. mjr_figure(viewport, &sim->figtimer, &sim->platform_ui->mjr_context());
  394. viewport.bottom += rect.height/4;
  395. mjr_figure(viewport, &sim->figsize, &sim->platform_ui->mjr_context());
  396. viewport.bottom += rect.height/4;
  397. mjr_figure(viewport, &sim->figcost, &sim->platform_ui->mjr_context());
  398. viewport.bottom += rect.height/4;
  399. mjr_figure(viewport, &sim->figconstraint, &sim->platform_ui->mjr_context());
  400. }
  401. // init sensor figure
  402. void InitializeSensor(mj::Simulate* sim) {
  403. mjvFigure& figsensor = sim->figsensor;
  404. // set figure to default
  405. mjv_defaultFigure(&figsensor);
  406. figsensor.figurergba[3] = 0.5f;
  407. // set flags
  408. figsensor.flg_extend = 1;
  409. figsensor.flg_barplot = 1;
  410. figsensor.flg_symmetric = 1;
  411. // title
  412. mju::strcpy_arr(figsensor.title, "Sensor data");
  413. // y-tick nubmer format
  414. mju::strcpy_arr(figsensor.yformat, "%.1f");
  415. // grid size
  416. figsensor.gridsize[0] = 2;
  417. figsensor.gridsize[1] = 3;
  418. // minimum range
  419. figsensor.range[0][0] = 0;
  420. figsensor.range[0][1] = 0;
  421. figsensor.range[1][0] = -1;
  422. figsensor.range[1][1] = 1;
  423. }
  424. // update sensor figure
  425. void UpdateSensor(mj::Simulate* sim, const mjModel* m, const mjData* d) {
  426. mjvFigure& figsensor = sim->figsensor;
  427. static const int maxline = 10;
  428. // clear linepnt
  429. for (int i=0; i<maxline; i++) {
  430. figsensor.linepnt[i] = 0;
  431. }
  432. // start with line 0
  433. int lineid = 0;
  434. // loop over sensors
  435. for (int n=0; n<m->nsensor; n++) {
  436. // go to next line if type is different
  437. if (n>0 && m->sensor_type[n]!=m->sensor_type[n-1]) {
  438. lineid = mjMIN(lineid+1, maxline-1);
  439. }
  440. // get info about this sensor
  441. mjtNum cutoff = (m->sensor_cutoff[n]>0 ? m->sensor_cutoff[n] : 1);
  442. int adr = m->sensor_adr[n];
  443. int dim = m->sensor_dim[n];
  444. // data pointer in line
  445. int p = figsensor.linepnt[lineid];
  446. // fill in data for this sensor
  447. for (int i=0; i<dim; i++) {
  448. // check size
  449. if ((p+2*i)>=mjMAXLINEPNT/2) {
  450. break;
  451. }
  452. // x
  453. figsensor.linedata[lineid][2*p+4*i] = adr+i;
  454. figsensor.linedata[lineid][2*p+4*i+2] = adr+i;
  455. // y
  456. figsensor.linedata[lineid][2*p+4*i+1] = 0;
  457. figsensor.linedata[lineid][2*p+4*i+3] = d->sensordata[adr+i]/cutoff;
  458. }
  459. // update linepnt
  460. figsensor.linepnt[lineid] = mjMIN(mjMAXLINEPNT-1, figsensor.linepnt[lineid]+2*dim);
  461. }
  462. }
  463. // show sensor figure
  464. void ShowSensor(mj::Simulate* sim, mjrRect rect) {
  465. // constant width with and without profiler
  466. int width = sim->profiler ? rect.width/3 : rect.width/4;
  467. // render figure on the right
  468. mjrRect viewport = {
  469. rect.left + rect.width - width,
  470. rect.bottom,
  471. width,
  472. rect.height/3
  473. };
  474. mjr_figure(viewport, &sim->figsensor, &sim->platform_ui->mjr_context());
  475. }
  476. // load state from history buffer
  477. static void LoadScrubState(mj::Simulate* sim) {
  478. // get index into circular buffer
  479. int i = (sim->scrub_index + sim->history_cursor_) % sim->nhistory_;
  480. i = (i + sim->nhistory_) % sim->nhistory_;
  481. // load state
  482. mjtNum* state = &sim->history_[i * sim->state_size_];
  483. mj_setState(sim->m_, sim->d_, state, mjSTATE_INTEGRATION);
  484. // call forward dynamics
  485. mj_forward(sim->m_, sim->d_);
  486. }
  487. // update an entire section of ui0
  488. static void mjui0_update_section(mj::Simulate* sim, int section) {
  489. mjui_update(section, -1, &sim->ui0, &sim->uistate, &sim->platform_ui->mjr_context());
  490. }
  491. // prepare info text
  492. void UpdateInfoText(mj::Simulate* sim, const mjModel* m, const mjData* d,
  493. char (&title)[mj::Simulate::kMaxFilenameLength],
  494. char (&content)[mj::Simulate::kMaxFilenameLength]) {
  495. char tmp[20];
  496. // number of islands with statistics
  497. int nisland = mjMIN(d->solver_nisland, mjNISLAND);
  498. // compute solver error (maximum over islands)
  499. mjtNum solerr = 0;
  500. for (int i=0; i < nisland; i++) {
  501. mjtNum solerr_i = 0;
  502. if (d->solver_niter[i]) {
  503. int ind = mjMIN(d->solver_niter[i], mjNSOLVER) - 1;
  504. const mjSolverStat* stat = d->solver + i*mjNSOLVER + ind;
  505. solerr_i = mju_min(stat->improvement, stat->gradient);
  506. if (solerr_i==0) {
  507. solerr_i = mju_max(stat->improvement, stat->gradient);
  508. }
  509. }
  510. solerr = mju_max(solerr, solerr_i);
  511. }
  512. solerr = mju_log10(mju_max(mjMINVAL, solerr));
  513. // format FPS text
  514. char fps[10];
  515. if (sim->fps_ < 1) {
  516. mju::sprintf_arr(fps, "%0.1f ", sim->fps_);
  517. } else {
  518. mju::sprintf_arr(fps, "%.0f ", sim->fps_);
  519. }
  520. // total iterations of all islands with statistics
  521. int solver_niter = 0;
  522. for (int i=0; i < nisland; i++) {
  523. solver_niter += d->solver_niter[i];
  524. }
  525. // prepare info text
  526. mju::strcpy_arr(title, "Time\nSize\nCPU\nSolver \nFPS\nMemory");
  527. mju::sprintf_arr(content,
  528. "%-9.3f\n%d (%d con)\n%.3f\n%.1f (%d it)\n%s\n%.1f%% of %s",
  529. d->time,
  530. d->nefc, d->ncon,
  531. sim->run ?
  532. d->timer[mjTIMER_STEP].duration / mjMAX(1, d->timer[mjTIMER_STEP].number) :
  533. d->timer[mjTIMER_FORWARD].duration / mjMAX(1, d->timer[mjTIMER_FORWARD].number),
  534. solerr, solver_niter,
  535. fps,
  536. 100*d->maxuse_arena/(double)(d->narena),
  537. mju_writeNumBytes(d->narena));
  538. // add Energy if enabled
  539. {
  540. if (mjENABLED(mjENBL_ENERGY)) {
  541. mju::sprintf_arr(tmp, "\n%.3f", d->energy[0]+d->energy[1]);
  542. mju::strcat_arr(content, tmp);
  543. mju::strcat_arr(title, "\nEnergy");
  544. }
  545. // add FwdInv if enabled
  546. if (mjENABLED(mjENBL_FWDINV)) {
  547. mju::sprintf_arr(tmp, "\n%.1f %.1f",
  548. mju_log10(mju_max(mjMINVAL, d->solver_fwdinv[0])),
  549. mju_log10(mju_max(mjMINVAL, d->solver_fwdinv[1])));
  550. mju::strcat_arr(content, tmp);
  551. mju::strcat_arr(title, "\nFwdInv");
  552. }
  553. // add islands if enabled
  554. if (mjENABLED(mjENBL_ISLAND)) {
  555. mju::sprintf_arr(tmp, "\n%d", d->nisland);
  556. mju::strcat_arr(content, tmp);
  557. mju::strcat_arr(title, "\nIslands");
  558. }
  559. }
  560. }
  561. // sprintf forwarding, to avoid compiler warning in x-macro
  562. void PrintField(char (&str)[mjMAXUINAME], void* ptr) {
  563. mju::sprintf_arr(str, "%g", *static_cast<mjtNum*>(ptr));
  564. }
  565. // update watch
  566. void UpdateWatch(mj::Simulate* sim, const mjModel* m, const mjData* d) {
  567. // clear
  568. sim->ui0.sect[SECT_WATCH].item[2].multi.nelem = 1;
  569. mju::strcpy_arr(sim->ui0.sect[SECT_WATCH].item[2].multi.name[0], "invalid field");
  570. // prepare symbols needed by xmacro
  571. MJDATA_POINTERS_PREAMBLE(m);
  572. // find specified field in mjData arrays, update value
  573. #define X(TYPE, NAME, NR, NC) \
  574. if (!mju::strcmp_arr(#NAME, sim->field) && \
  575. !mju::strcmp_arr(#TYPE, "mjtNum")) { \
  576. if (sim->index >= 0 && sim->index < m->NR * NC) { \
  577. PrintField(sim->ui0.sect[SECT_WATCH].item[2].multi.name[0], d->NAME + sim->index); \
  578. } else { \
  579. mju::strcpy_arr(sim->ui0.sect[SECT_WATCH].item[2].multi.name[0], "invalid index"); \
  580. } \
  581. return; \
  582. }
  583. MJDATA_POINTERS
  584. #undef X
  585. }
  586. //---------------------------------- UI construction -----------------------------------------------
  587. // make physics section of UI
  588. void MakePhysicsSection(mj::Simulate* sim) {
  589. mjOption* opt = sim->is_passive_ ? &sim->scnstate_.model.opt : &sim->m_->opt;
  590. mjuiDef defPhysics[] = {
  591. {mjITEM_SECTION, "Physics", mjPRESERVE, nullptr, "AP"},
  592. {mjITEM_SELECT, "Integrator", 2, &(opt->integrator), "Euler\nRK4\nimplicit\nimplicitfast"},
  593. {mjITEM_SELECT, "Cone", 2, &(opt->cone), "Pyramidal\nElliptic"},
  594. {mjITEM_SELECT, "Jacobian", 2, &(opt->jacobian), "Dense\nSparse\nAuto"},
  595. {mjITEM_SELECT, "Solver", 2, &(opt->solver), "PGS\nCG\nNewton"},
  596. {mjITEM_SEPARATOR, "Algorithmic Parameters", mjPRESERVE},
  597. {mjITEM_EDITNUM, "Timestep", 2, &(opt->timestep), "1 0 1"},
  598. {mjITEM_EDITINT, "Iterations", 2, &(opt->iterations), "1 0 1000"},
  599. {mjITEM_EDITNUM, "Tolerance", 2, &(opt->tolerance), "1 0 1"},
  600. {mjITEM_EDITINT, "LS Iter", 2, &(opt->ls_iterations), "1 0 100"},
  601. {mjITEM_EDITNUM, "LS Tol", 2, &(opt->ls_tolerance), "1 0 0.1"},
  602. {mjITEM_EDITINT, "Noslip Iter", 2, &(opt->noslip_iterations), "1 0 1000"},
  603. {mjITEM_EDITNUM, "Noslip Tol", 2, &(opt->noslip_tolerance), "1 0 1"},
  604. {mjITEM_EDITINT, "CCD Iter", 2, &(opt->ccd_iterations), "1 0 1000"},
  605. {mjITEM_EDITNUM, "CCD Tol", 2, &(opt->ccd_tolerance), "1 0 1"},
  606. {mjITEM_EDITNUM, "API Rate", 2, &(opt->apirate), "1 0 1000"},
  607. {mjITEM_EDITINT, "SDF Iter", 2, &(opt->sdf_iterations), "1 1 20"},
  608. {mjITEM_EDITINT, "SDF Init", 2, &(opt->sdf_initpoints), "1 1 100"},
  609. {mjITEM_SEPARATOR, "Physical Parameters", mjPRESERVE},
  610. {mjITEM_EDITNUM, "Gravity", 2, opt->gravity, "3"},
  611. {mjITEM_EDITNUM, "Wind", 2, opt->wind, "3"},
  612. {mjITEM_EDITNUM, "Magnetic", 2, opt->magnetic, "3"},
  613. {mjITEM_EDITNUM, "Density", 2, &(opt->density), "1"},
  614. {mjITEM_EDITNUM, "Viscosity", 2, &(opt->viscosity), "1"},
  615. {mjITEM_EDITNUM, "Imp Ratio", 2, &(opt->impratio), "1"},
  616. {mjITEM_SEPARATOR, "Disable Flags", mjPRESERVE},
  617. {mjITEM_END}
  618. };
  619. mjuiDef defEnableFlags[] = {
  620. {mjITEM_SEPARATOR, "Enable Flags", mjPRESERVE},
  621. {mjITEM_END}
  622. };
  623. mjuiDef defOverride[] = {
  624. {mjITEM_SEPARATOR, "Contact Override", mjPRESERVE},
  625. {mjITEM_EDITNUM, "Margin", 2, &(opt->o_margin), "1"},
  626. {mjITEM_EDITNUM, "Sol Imp", 2, &(opt->o_solimp), "5"},
  627. {mjITEM_EDITNUM, "Sol Ref", 2, &(opt->o_solref), "2"},
  628. {mjITEM_EDITNUM, "Friction", 2, &(opt->o_friction), "5"},
  629. {mjITEM_END}
  630. };
  631. mjuiDef defDisableActuator[] = {
  632. {mjITEM_SEPARATOR, "Actuator Group Enable", mjPRESERVE},
  633. {mjITEM_CHECKBYTE, "Act Group 0", 2, sim->enableactuator+0, ""},
  634. {mjITEM_CHECKBYTE, "Act Group 1", 2, sim->enableactuator+1, ""},
  635. {mjITEM_CHECKBYTE, "Act Group 2", 2, sim->enableactuator+2, ""},
  636. {mjITEM_CHECKBYTE, "Act Group 3", 2, sim->enableactuator+3, ""},
  637. {mjITEM_CHECKBYTE, "Act Group 4", 2, sim->enableactuator+4, ""},
  638. {mjITEM_CHECKBYTE, "Act Group 5", 2, sim->enableactuator+5, ""},
  639. {mjITEM_END}
  640. };
  641. // add physics
  642. mjui_add(&sim->ui0, defPhysics);
  643. // add flags programmatically
  644. mjuiDef defFlag[] = {
  645. {mjITEM_CHECKINT, "", 2, nullptr, ""},
  646. {mjITEM_END}
  647. };
  648. for (int i=0; i<mjNDISABLE; i++) {
  649. mju::strcpy_arr(defFlag[0].name, mjDISABLESTRING[i]);
  650. defFlag[0].pdata = sim->disable + i;
  651. mjui_add(&sim->ui0, defFlag);
  652. }
  653. mjui_add(&sim->ui0, defEnableFlags);
  654. for (int i=0; i<mjNENABLE; i++) {
  655. mju::strcpy_arr(defFlag[0].name, mjENABLESTRING[i]);
  656. defFlag[0].pdata = sim->enable + i;
  657. mjui_add(&sim->ui0, defFlag);
  658. }
  659. // add contact override
  660. mjui_add(&sim->ui0, defOverride);
  661. // add actuator group enable/disable
  662. mjui_add(&sim->ui0, defDisableActuator);
  663. // make some subsections closed by default
  664. for (int i=0; i < sim->ui0.sect[SECT_PHYSICS].nitem; i++) {
  665. mjuiItem* it = sim->ui0.sect[SECT_PHYSICS].item + i;
  666. // close less useful subsections
  667. if (it->type == mjITEM_SEPARATOR) {
  668. if (mju::strcmp_arr(it->name, "Actuator Group Enable") &&
  669. mju::strcmp_arr(it->name, "Contact Override") &&
  670. mju::strcmp_arr(it->name, "Physical Parameters")) {
  671. it->state = mjSEPCLOSED+1;
  672. }
  673. }
  674. }
  675. }
  676. // make rendering section of UI
  677. void MakeRenderingSection(mj::Simulate* sim, const mjModel* m) {
  678. mjuiDef defRendering[] = {
  679. {mjITEM_SECTION, "Rendering", mjPRESERVE, nullptr, "AR"},
  680. {mjITEM_SELECT, "Camera", 2, &(sim->camera), "Free\nTracking"},
  681. {mjITEM_SELECT, "Label", 2, &(sim->opt.label),
  682. "None\nBody\nJoint\nGeom\nSite\nCamera\nLight\nTendon\n"
  683. "Actuator\nConstraint\nFlex\nSkin\nSelection\nSel Pnt\nContact\nForce\nIsland"
  684. },
  685. {mjITEM_SELECT, "Frame", 2, &(sim->opt.frame),
  686. "None\nBody\nGeom\nSite\nCamera\nLight\nContact\nWorld"
  687. },
  688. {mjITEM_BUTTON, "Copy camera", 2, nullptr, ""},
  689. {mjITEM_SEPARATOR, "Model Elements", 1},
  690. {mjITEM_END}
  691. };
  692. mjuiDef defOpenGL[] = {
  693. {mjITEM_SEPARATOR, "OpenGL Effects", 1},
  694. {mjITEM_END}
  695. };
  696. // add model cameras, up to UI limit
  697. for (int i=0; i<mjMIN(m->ncam, mjMAXUIMULTI-2); i++) {
  698. // prepare name
  699. char camname[mjMAXUINAME] = "\n";
  700. if (m->names[m->name_camadr[i]]) {
  701. mju::strcat_arr(camname, m->names+m->name_camadr[i]);
  702. } else {
  703. mju::sprintf_arr(camname, "\nCamera %d", i);
  704. }
  705. // check string length
  706. if (mju::strlen_arr(camname) + mju::strlen_arr(defRendering[1].other)>=mjMAXUITEXT-1) {
  707. break;
  708. }
  709. // add camera
  710. mju::strcat_arr(defRendering[1].other, camname);
  711. }
  712. // add rendering standard
  713. mjui_add(&sim->ui0, defRendering);
  714. // add flags programmatically
  715. mjuiDef defFlag[] = {
  716. {mjITEM_CHECKBYTE, "", 2, nullptr, ""},
  717. {mjITEM_END}
  718. };
  719. for (int i=0; i<mjNVISFLAG; i++) {
  720. // set name
  721. mju::strcpy_arr(defFlag[0].name, mjVISSTRING[i][0]);
  722. // set shortcut and data
  723. if (mjVISSTRING[i][2][0]) {
  724. mju::sprintf_arr(defFlag[0].other, " %s", mjVISSTRING[i][2]);
  725. } else {
  726. mju::sprintf_arr(defFlag[0].other, "");
  727. }
  728. defFlag[0].pdata = sim->opt.flags + i;
  729. mjui_add(&sim->ui0, defFlag);
  730. }
  731. // create tree slider
  732. mjuiDef defTree[] = {
  733. {mjITEM_SLIDERINT, "Tree depth", 2, &sim->opt.bvh_depth, "0 20"},
  734. {mjITEM_SLIDERINT, "Flex layer", 2, &sim->opt.flex_layer, "0 10"},
  735. {mjITEM_END}
  736. };
  737. mjui_add(&sim->ui0, defTree);
  738. // add rendering flags
  739. mjui_add(&sim->ui0, defOpenGL);
  740. for (int i=0; i<mjNRNDFLAG; i++) {
  741. // set name
  742. mju::strcpy_arr(defFlag[0].name, mjRNDSTRING[i][0]);
  743. // set shortcut and data
  744. if (mjRNDSTRING[i][2][0]) {
  745. mju::sprintf_arr(defFlag[0].other, " %s", mjRNDSTRING[i][2]);
  746. } else {
  747. mju::sprintf_arr(defFlag[0].other, "");
  748. }
  749. defFlag[0].pdata = sim->scn.flags + i;
  750. mjui_add(&sim->ui0, defFlag);
  751. }
  752. }
  753. // make visualization section of UI
  754. void MakeVisualizationSection(mj::Simulate* sim, const mjModel* m) {
  755. mjStatistic* stat = sim->is_passive_ ? &sim->scnstate_.model.stat : &sim->m_->stat;
  756. mjVisual* vis = sim->is_passive_ ? &sim->scnstate_.model.vis : &sim->m_->vis;
  757. mjuiDef defVisualization[] = {
  758. {mjITEM_SECTION, "Visualization", mjPRESERVE, nullptr, "AV"},
  759. {mjITEM_SEPARATOR, "Headlight", 1},
  760. {mjITEM_RADIO, "Active", 5, &(vis->headlight.active), "Off\nOn"},
  761. {mjITEM_EDITFLOAT, "Ambient", 2, &(vis->headlight.ambient), "3"},
  762. {mjITEM_EDITFLOAT, "Diffuse", 2, &(vis->headlight.diffuse), "3"},
  763. {mjITEM_EDITFLOAT, "Specular", 2, &(vis->headlight.specular), "3"},
  764. {mjITEM_SEPARATOR, "Free Camera", 1},
  765. {mjITEM_RADIO, "Orthographic", 2, &(vis->global.orthographic), "No\nYes"},
  766. {mjITEM_EDITFLOAT, "Field of view", 2, &(vis->global.fovy), "1"},
  767. {mjITEM_EDITNUM, "Center", 2, &(stat->center), "3"},
  768. {mjITEM_EDITFLOAT, "Azimuth", 2, &(vis->global.azimuth), "1"},
  769. {mjITEM_EDITFLOAT, "Elevation", 2, &(vis->global.elevation), "1"},
  770. {mjITEM_BUTTON, "Align", 2, nullptr, "CA"},
  771. {mjITEM_SEPARATOR, "Global", 1},
  772. {mjITEM_EDITNUM, "Extent", 2, &(stat->extent), "1"},
  773. {mjITEM_RADIO, "Inertia", 5, &(vis->global.ellipsoidinertia), "Box\nEllipsoid"},
  774. {mjITEM_RADIO, "BVH active", 5, &(vis->global.bvactive), "False\nTrue"},
  775. {mjITEM_SEPARATOR, "Map", 1},
  776. {mjITEM_EDITFLOAT, "Stiffness", 2, &(vis->map.stiffness), "1"},
  777. {mjITEM_EDITFLOAT, "Rot stiffness", 2, &(vis->map.stiffnessrot), "1"},
  778. {mjITEM_EDITFLOAT, "Force", 2, &(vis->map.force), "1"},
  779. {mjITEM_EDITFLOAT, "Torque", 2, &(vis->map.torque), "1"},
  780. {mjITEM_EDITFLOAT, "Alpha", 2, &(vis->map.alpha), "1"},
  781. {mjITEM_EDITFLOAT, "Fog start", 2, &(vis->map.fogstart), "1"},
  782. {mjITEM_EDITFLOAT, "Fog end", 2, &(vis->map.fogend), "1"},
  783. {mjITEM_EDITFLOAT, "Z near", 2, &(vis->map.znear), "1"},
  784. {mjITEM_EDITFLOAT, "Z far", 2, &(vis->map.zfar), "1"},
  785. {mjITEM_EDITFLOAT, "Haze", 2, &(vis->map.haze), "1"},
  786. {mjITEM_EDITFLOAT, "Shadow clip", 2, &(vis->map.shadowclip), "1"},
  787. {mjITEM_EDITFLOAT, "Shadow scale", 2, &(vis->map.shadowscale), "1"},
  788. {mjITEM_SEPARATOR, "Scale", mjPRESERVE},
  789. {mjITEM_EDITNUM, "All (meansize)", 2, &(stat->meansize), "1"},
  790. {mjITEM_EDITFLOAT, "Force width", 2, &(vis->scale.forcewidth), "1"},
  791. {mjITEM_EDITFLOAT, "Contact width", 2, &(vis->scale.contactwidth), "1"},
  792. {mjITEM_EDITFLOAT, "Contact height", 2, &(vis->scale.contactheight), "1"},
  793. {mjITEM_EDITFLOAT, "Connect", 2, &(vis->scale.connect), "1"},
  794. {mjITEM_EDITFLOAT, "Com", 2, &(vis->scale.com), "1"},
  795. {mjITEM_EDITFLOAT, "Camera", 2, &(vis->scale.camera), "1"},
  796. {mjITEM_EDITFLOAT, "Light", 2, &(vis->scale.light), "1"},
  797. {mjITEM_EDITFLOAT, "Select point", 2, &(vis->scale.selectpoint), "1"},
  798. {mjITEM_EDITFLOAT, "Joint length", 2, &(vis->scale.jointlength), "1"},
  799. {mjITEM_EDITFLOAT, "Joint width", 2, &(vis->scale.jointwidth), "1"},
  800. {mjITEM_EDITFLOAT, "Actuator length", 2, &(vis->scale.actuatorlength), "1"},
  801. {mjITEM_EDITFLOAT, "Actuator width", 2, &(vis->scale.actuatorwidth), "1"},
  802. {mjITEM_EDITFLOAT, "Frame length", 2, &(vis->scale.framelength), "1"},
  803. {mjITEM_EDITFLOAT, "Frame width", 2, &(vis->scale.framewidth), "1"},
  804. {mjITEM_EDITFLOAT, "Constraint", 2, &(vis->scale.constraint), "1"},
  805. {mjITEM_EDITFLOAT, "Slider-crank", 2, &(vis->scale.slidercrank), "1"},
  806. {mjITEM_SEPARATOR, "RGBA", mjPRESERVE},
  807. {mjITEM_EDITFLOAT, "fog", 2, &(vis->rgba.fog), "4"},
  808. {mjITEM_EDITFLOAT, "haze", 2, &(vis->rgba.haze), "4"},
  809. {mjITEM_EDITFLOAT, "force", 2, &(vis->rgba.force), "4"},
  810. {mjITEM_EDITFLOAT, "inertia", 2, &(vis->rgba.inertia), "4"},
  811. {mjITEM_EDITFLOAT, "joint", 2, &(vis->rgba.joint), "4"},
  812. {mjITEM_EDITFLOAT, "actuator", 2, &(vis->rgba.actuator), "4"},
  813. {mjITEM_EDITFLOAT, "actnegative", 2, &(vis->rgba.actuatornegative), "4"},
  814. {mjITEM_EDITFLOAT, "actpositive", 2, &(vis->rgba.actuatorpositive), "4"},
  815. {mjITEM_EDITFLOAT, "com", 2, &(vis->rgba.com), "4"},
  816. {mjITEM_EDITFLOAT, "camera", 2, &(vis->rgba.camera), "4"},
  817. {mjITEM_EDITFLOAT, "light", 2, &(vis->rgba.light), "4"},
  818. {mjITEM_EDITFLOAT, "selectpoint", 2, &(vis->rgba.selectpoint), "4"},
  819. {mjITEM_EDITFLOAT, "connect", 2, &(vis->rgba.connect), "4"},
  820. {mjITEM_EDITFLOAT, "contactpoint", 2, &(vis->rgba.contactpoint), "4"},
  821. {mjITEM_EDITFLOAT, "contactforce", 2, &(vis->rgba.contactforce), "4"},
  822. {mjITEM_EDITFLOAT, "contactfriction", 2, &(vis->rgba.contactfriction), "4"},
  823. {mjITEM_EDITFLOAT, "contacttorque", 2, &(vis->rgba.contacttorque), "4"},
  824. {mjITEM_EDITFLOAT, "contactgap", 2, &(vis->rgba.contactgap), "4"},
  825. {mjITEM_EDITFLOAT, "rangefinder", 2, &(vis->rgba.rangefinder), "4"},
  826. {mjITEM_EDITFLOAT, "constraint", 2, &(vis->rgba.constraint), "4"},
  827. {mjITEM_EDITFLOAT, "slidercrank", 2, &(vis->rgba.slidercrank), "4"},
  828. {mjITEM_EDITFLOAT, "crankbroken", 2, &(vis->rgba.crankbroken), "4"},
  829. {mjITEM_EDITFLOAT, "frustum", 2, &(vis->rgba.frustum), "4"},
  830. {mjITEM_EDITFLOAT, "bv", 2, &(vis->rgba.bv), "4"},
  831. {mjITEM_EDITFLOAT, "bvactive", 2, &(vis->rgba.bvactive), "4"},
  832. {mjITEM_END}
  833. };
  834. // add visualization section
  835. mjui_add(&sim->ui0, defVisualization);
  836. }
  837. // make group section of UI
  838. void MakeGroupSection(mj::Simulate* sim) {
  839. mjuiDef defGroup[] = {
  840. {mjITEM_SECTION, "Group enable", mjPRESERVE, nullptr, "AG"},
  841. {mjITEM_SEPARATOR, "Geom groups", 1},
  842. {mjITEM_CHECKBYTE, "Geom 0", 2, sim->opt.geomgroup, " 0"},
  843. {mjITEM_CHECKBYTE, "Geom 1", 2, sim->opt.geomgroup+1, " 1"},
  844. {mjITEM_CHECKBYTE, "Geom 2", 2, sim->opt.geomgroup+2, " 2"},
  845. {mjITEM_CHECKBYTE, "Geom 3", 2, sim->opt.geomgroup+3, " 3"},
  846. {mjITEM_CHECKBYTE, "Geom 4", 2, sim->opt.geomgroup+4, " 4"},
  847. {mjITEM_CHECKBYTE, "Geom 5", 2, sim->opt.geomgroup+5, " 5"},
  848. {mjITEM_SEPARATOR, "Site groups", 1},
  849. {mjITEM_CHECKBYTE, "Site 0", 2, sim->opt.sitegroup, "S0"},
  850. {mjITEM_CHECKBYTE, "Site 1", 2, sim->opt.sitegroup+1, "S1"},
  851. {mjITEM_CHECKBYTE, "Site 2", 2, sim->opt.sitegroup+2, "S2"},
  852. {mjITEM_CHECKBYTE, "Site 3", 2, sim->opt.sitegroup+3, "S3"},
  853. {mjITEM_CHECKBYTE, "Site 4", 2, sim->opt.sitegroup+4, "S4"},
  854. {mjITEM_CHECKBYTE, "Site 5", 2, sim->opt.sitegroup+5, "S5"},
  855. {mjITEM_SEPARATOR, "Joint groups", 1},
  856. {mjITEM_CHECKBYTE, "Joint 0", 2, sim->opt.jointgroup, ""},
  857. {mjITEM_CHECKBYTE, "Joint 1", 2, sim->opt.jointgroup+1, ""},
  858. {mjITEM_CHECKBYTE, "Joint 2", 2, sim->opt.jointgroup+2, ""},
  859. {mjITEM_CHECKBYTE, "Joint 3", 2, sim->opt.jointgroup+3, ""},
  860. {mjITEM_CHECKBYTE, "Joint 4", 2, sim->opt.jointgroup+4, ""},
  861. {mjITEM_CHECKBYTE, "Joint 5", 2, sim->opt.jointgroup+5, ""},
  862. {mjITEM_SEPARATOR, "Tendon groups", 1},
  863. {mjITEM_CHECKBYTE, "Tendon 0", 2, sim->opt.tendongroup, ""},
  864. {mjITEM_CHECKBYTE, "Tendon 1", 2, sim->opt.tendongroup+1, ""},
  865. {mjITEM_CHECKBYTE, "Tendon 2", 2, sim->opt.tendongroup+2, ""},
  866. {mjITEM_CHECKBYTE, "Tendon 3", 2, sim->opt.tendongroup+3, ""},
  867. {mjITEM_CHECKBYTE, "Tendon 4", 2, sim->opt.tendongroup+4, ""},
  868. {mjITEM_CHECKBYTE, "Tendon 5", 2, sim->opt.tendongroup+5, ""},
  869. {mjITEM_SEPARATOR, "Actuator groups", 1},
  870. {mjITEM_CHECKBYTE, "Actuator 0", 2, sim->opt.actuatorgroup, ""},
  871. {mjITEM_CHECKBYTE, "Actuator 1", 2, sim->opt.actuatorgroup+1, ""},
  872. {mjITEM_CHECKBYTE, "Actuator 2", 2, sim->opt.actuatorgroup+2, ""},
  873. {mjITEM_CHECKBYTE, "Actuator 3", 2, sim->opt.actuatorgroup+3, ""},
  874. {mjITEM_CHECKBYTE, "Actuator 4", 2, sim->opt.actuatorgroup+4, ""},
  875. {mjITEM_CHECKBYTE, "Actuator 5", 2, sim->opt.actuatorgroup+5, ""},
  876. {mjITEM_SEPARATOR, "Flex groups", 1},
  877. {mjITEM_CHECKBYTE, "Flex 0", 2, sim->opt.flexgroup, ""},
  878. {mjITEM_CHECKBYTE, "Flex 1", 2, sim->opt.flexgroup+1, ""},
  879. {mjITEM_CHECKBYTE, "Flex 2", 2, sim->opt.flexgroup+2, ""},
  880. {mjITEM_CHECKBYTE, "Flex 3", 2, sim->opt.flexgroup+3, ""},
  881. {mjITEM_CHECKBYTE, "Flex 4", 2, sim->opt.flexgroup+4, ""},
  882. {mjITEM_CHECKBYTE, "Flex 5", 2, sim->opt.flexgroup+5, ""},
  883. {mjITEM_SEPARATOR, "Skin groups", 1},
  884. {mjITEM_CHECKBYTE, "Skin 0", 2, sim->opt.skingroup, ""},
  885. {mjITEM_CHECKBYTE, "Skin 1", 2, sim->opt.skingroup+1, ""},
  886. {mjITEM_CHECKBYTE, "Skin 2", 2, sim->opt.skingroup+2, ""},
  887. {mjITEM_CHECKBYTE, "Skin 3", 2, sim->opt.skingroup+3, ""},
  888. {mjITEM_CHECKBYTE, "Skin 4", 2, sim->opt.skingroup+4, ""},
  889. {mjITEM_CHECKBYTE, "Skin 5", 2, sim->opt.skingroup+5, ""},
  890. {mjITEM_END}
  891. };
  892. // add section
  893. mjui_add(&sim->ui0, defGroup);
  894. }
  895. // make joint section of UI
  896. void MakeJointSection(mj::Simulate* sim) {
  897. mjuiDef defJoint[] = {
  898. {mjITEM_SECTION, "Joint", mjPRESERVE, nullptr, "AJ"},
  899. {mjITEM_END}
  900. };
  901. mjuiDef defSlider[] = {
  902. {mjITEM_SLIDERNUM, "", 2, nullptr, "0 1"},
  903. {mjITEM_END}
  904. };
  905. // add section
  906. mjui_add(&sim->ui1, defJoint);
  907. defSlider[0].state = 4;
  908. // add scalar joints, exit if UI limit reached
  909. int itemcnt = 0;
  910. for (int i=0; i < sim->jnt_type_.size() && itemcnt<mjMAXUIITEM; i++) {
  911. if ((sim->jnt_type_[i]==mjJNT_HINGE || sim->jnt_type_[i]==mjJNT_SLIDE)) {
  912. // skip if joint group is disabled
  913. if (!sim->opt.jointgroup[mjMAX(0, mjMIN(mjNGROUP-1, sim->jnt_group_[i]))]) {
  914. continue;
  915. }
  916. // set data and name
  917. if (!sim->is_passive_) {
  918. defSlider[0].pdata = &sim->d_->qpos[sim->m_->jnt_qposadr[i]];
  919. } else {
  920. defSlider[0].pdata = &sim->qpos_[sim->jnt_qposadr_[i]];
  921. }
  922. if (!sim->jnt_names_[i].empty()) {
  923. mju::strcpy_arr(defSlider[0].name, sim->jnt_names_[i].c_str());
  924. } else {
  925. mju::sprintf_arr(defSlider[0].name, "joint %d", i);
  926. }
  927. // set range
  928. if (sim->jnt_range_[i].has_value())
  929. mju::sprintf_arr(defSlider[0].other, "%.4g %.4g",
  930. sim->jnt_range_[i]->first, sim->jnt_range_[i]->second);
  931. else if (sim->jnt_type_[i]==mjJNT_SLIDE) {
  932. mju::strcpy_arr(defSlider[0].other, "-1 1");
  933. } else {
  934. mju::strcpy_arr(defSlider[0].other, "-3.1416 3.1416");
  935. }
  936. // add and count
  937. mjui_add(&sim->ui1, defSlider);
  938. itemcnt++;
  939. }
  940. }
  941. }
  942. // make control section of UI
  943. void MakeControlSection(mj::Simulate* sim) {
  944. mjuiDef defControl[] = {
  945. {mjITEM_SECTION, "Control", mjPRESERVE, nullptr, "AC"},
  946. {mjITEM_BUTTON, "Clear all", 2},
  947. {mjITEM_END}
  948. };
  949. mjuiDef defSlider[] = {
  950. {mjITEM_SLIDERNUM, "", 2, nullptr, "0 1"},
  951. {mjITEM_END}
  952. };
  953. // add section
  954. mjui_add(&sim->ui1, defControl);
  955. // add controls, exit if UI limit reached (Clear button already added)
  956. int itemcnt = 1;
  957. for (int i=0; i < sim->actuator_ctrlrange_.size() && itemcnt<mjMAXUIITEM; i++) {
  958. // skip if actuator vis group is disabled
  959. int group = sim->actuator_group_[i];
  960. if (!sim->opt.actuatorgroup[mjMAX(0, mjMIN(mjNGROUP-1, group))]) {
  961. continue;
  962. }
  963. // grey out if actuator group is disabled
  964. if (group >= 0 && group <= 30 && sim->m_->opt.disableactuator & (1 << group)) {
  965. defSlider[0].state = 0;
  966. } else {
  967. defSlider[0].state = 2;
  968. }
  969. // set data and name
  970. if (!sim->is_passive_) {
  971. defSlider[0].pdata = &sim->d_->ctrl[i];
  972. } else {
  973. defSlider[0].pdata = &sim->ctrl_[i];
  974. }
  975. if (!sim->actuator_names_[i].empty()) {
  976. mju::strcpy_arr(defSlider[0].name, sim->actuator_names_[i].c_str());
  977. } else {
  978. mju::sprintf_arr(defSlider[0].name, "control %d", i);
  979. }
  980. // set range
  981. if (sim->actuator_ctrlrange_[i].has_value())
  982. mju::sprintf_arr(defSlider[0].other, "%.4g %.4g",
  983. sim->actuator_ctrlrange_[i]->first, sim->actuator_ctrlrange_[i]->second);
  984. else {
  985. mju::strcpy_arr(defSlider[0].other, "-1 1");
  986. }
  987. // add and count
  988. mjui_add(&sim->ui1, defSlider);
  989. itemcnt++;
  990. }
  991. }
  992. // make model-dependent UI sections
  993. void MakeUiSections(mj::Simulate* sim, const mjModel* m, const mjData* d) {
  994. // clear model-dependent sections of UI
  995. sim->ui0.nsect = SECT_PHYSICS;
  996. sim->ui1.nsect = 0;
  997. // make
  998. MakePhysicsSection(sim);
  999. MakeRenderingSection(sim, m);
  1000. MakeVisualizationSection(sim, m);
  1001. MakeGroupSection(sim);
  1002. MakeJointSection(sim);
  1003. MakeControlSection(sim);
  1004. }
  1005. //---------------------------------- utility functions ---------------------------------------------
  1006. // align and scale view
  1007. void AlignAndScaleView(mj::Simulate* sim, const mjModel* m) {
  1008. // use default free camera parameters
  1009. mjv_defaultFreeCamera(m, &sim->cam);
  1010. }
  1011. // copy qpos to clipboard as key
  1012. void CopyPose(mj::Simulate* sim, const mjModel* m, const mjData* d) {
  1013. char clipboard[5000] = "<key qpos='";
  1014. char buf[200];
  1015. // prepare string
  1016. for (int i=0; i<m->nq; i++) {
  1017. mju::sprintf_arr(buf, i==m->nq-1 ? "%g" : "%g ", d->qpos[i]);
  1018. mju::strcat_arr(clipboard, buf);
  1019. }
  1020. mju::strcat_arr(clipboard, "'/>");
  1021. // copy to clipboard
  1022. sim->platform_ui->SetClipboardString(clipboard);
  1023. }
  1024. // millisecond timer, for MuJoCo built-in profiler
  1025. mjtNum Timer() {
  1026. static auto start = mj::Simulate::Clock::now();
  1027. auto elapsed = Milliseconds(mj::Simulate::Clock::now() - start);
  1028. return elapsed.count();
  1029. }
  1030. // clear all times
  1031. void ClearTimers(mjData* d) {
  1032. for (int i=0; i<mjNTIMER; i++) {
  1033. d->timer[i].duration = 0;
  1034. d->timer[i].number = 0;
  1035. }
  1036. }
  1037. // copy current camera to clipboard as MJCF specification
  1038. void CopyCamera(mj::Simulate* sim) {
  1039. mjvGLCamera* camera = sim->scn.camera;
  1040. char clipboard[500];
  1041. mjtNum cam_right[3];
  1042. mjtNum cam_forward[3];
  1043. mjtNum cam_up[3];
  1044. // get camera spec from the GLCamera
  1045. mju_f2n(cam_forward, camera[0].forward, 3);
  1046. mju_f2n(cam_up, camera[0].up, 3);
  1047. mju_cross(cam_right, cam_forward, cam_up);
  1048. // make MJCF camera spec
  1049. mju::sprintf_arr(clipboard,
  1050. "<camera pos=\"%.3f %.3f %.3f\" xyaxes=\"%.3f %.3f %.3f %.3f %.3f %.3f\"/>\n",
  1051. (camera[0].pos[0] + camera[1].pos[0]) / 2,
  1052. (camera[0].pos[1] + camera[1].pos[1]) / 2,
  1053. (camera[0].pos[2] + camera[1].pos[2]) / 2,
  1054. cam_right[0], cam_right[1], cam_right[2],
  1055. camera[0].up[0], camera[0].up[1], camera[0].up[2]);
  1056. // copy spec into clipboard
  1057. sim->platform_ui->SetClipboardString(clipboard);
  1058. }
  1059. // update UI 0 when MuJoCo structures change (except for joint sliders)
  1060. void UpdateSettings(mj::Simulate* sim, const mjModel* m) {
  1061. // physics flags
  1062. for (int i=0; i<mjNDISABLE; i++) {
  1063. int new_value = ((m->opt.disableflags & (1<<i)) != 0);
  1064. if (sim->disable[i] != new_value) {
  1065. sim->disable[i] = new_value;
  1066. sim->pending_.ui_update_physics = true;
  1067. }
  1068. }
  1069. for (int i=0; i<mjNENABLE; i++) {
  1070. int new_value = ((m->opt.enableflags & (1<<i)) != 0);
  1071. if (sim->enable[i] != new_value) {
  1072. sim->enable[i] = new_value;
  1073. sim->pending_.ui_update_physics = true;
  1074. }
  1075. }
  1076. for (int i=0; i<mjNGROUP; i++) {
  1077. int enabled = ((m->opt.disableactuator & (1<<i)) == 0);
  1078. if (sim->enableactuator[i] != enabled) {
  1079. sim->enableactuator[i] = enabled;
  1080. sim->pending_.ui_update_physics = true;
  1081. sim->pending_.ui_remake_ctrl = true;
  1082. }
  1083. }
  1084. // camera
  1085. int old_camera = sim->camera;
  1086. if (sim->cam.type==mjCAMERA_FIXED) {
  1087. sim->camera = 2 + sim->cam.fixedcamid;
  1088. } else if (sim->cam.type==mjCAMERA_TRACKING) {
  1089. sim->camera = 1;
  1090. } else {
  1091. sim->camera = 0;
  1092. }
  1093. if (old_camera != sim->camera) {
  1094. sim->pending_.ui_update_rendering = true;
  1095. }
  1096. }
  1097. // Compute suitable font scale.
  1098. int ComputeFontScale(const mj::PlatformUIAdapter& platform_ui) {
  1099. // compute framebuffer-to-window ratio
  1100. auto [buf_width, buf_height] = platform_ui.GetFramebufferSize();
  1101. auto [win_width, win_height] = platform_ui.GetWindowSize();
  1102. double b2w = static_cast<double>(buf_width) / win_width;
  1103. // compute PPI
  1104. double PPI = b2w * platform_ui.GetDisplayPixelsPerInch();
  1105. // estimate font scaling, guard against unrealistic PPI
  1106. int fs;
  1107. if (buf_width > win_width) {
  1108. fs = mju_round(b2w * 100);
  1109. } else if (PPI>50 && PPI<350) {
  1110. fs = mju_round(PPI);
  1111. } else {
  1112. fs = 150;
  1113. }
  1114. fs = mju_round(fs * 0.02) * 50;
  1115. fs = mjMIN(300, mjMAX(100, fs));
  1116. return fs;
  1117. }
  1118. //---------------------------------- UI handlers ---------------------------------------------------
  1119. // determine enable/disable item state given category
  1120. int UiPredicate(int category, void* userdata) {
  1121. mj::Simulate* sim = static_cast<mj::Simulate*>(userdata);
  1122. switch (category) {
  1123. case 2: // require model
  1124. return sim->m_ || sim->is_passive_;
  1125. case 3: // require model and nkey
  1126. return (sim->m_ || sim->is_passive_) && sim->nkey_;
  1127. case 4: // require model and paused
  1128. return sim->m_ && !sim->run;
  1129. case 5: // require model and fully managed mode
  1130. return !sim->is_passive_ && sim->m_;
  1131. default:
  1132. return 1;
  1133. }
  1134. }
  1135. // set window layout
  1136. void UiLayout(mjuiState* state) {
  1137. mj::Simulate* sim = static_cast<mj::Simulate*>(state->userdata);
  1138. mjrRect* rect = state->rect;
  1139. // set number of rectangles
  1140. state->nrect = 4;
  1141. // rect 1: UI 0
  1142. rect[1].left = 0;
  1143. rect[1].width = sim->ui0_enable ? sim->ui0.width : 0;
  1144. rect[1].bottom = 0;
  1145. rect[1].height = rect[0].height;
  1146. // rect 2: UI 1
  1147. rect[2].width = sim->ui1_enable ? sim->ui1.width : 0;
  1148. rect[2].left = mjMAX(0, rect[0].width - rect[2].width);
  1149. rect[2].bottom = 0;
  1150. rect[2].height = rect[0].height;
  1151. // rect 3: 3D plot (everything else is an overlay)
  1152. rect[3].left = rect[1].width;
  1153. rect[3].width = mjMAX(0, rect[0].width - rect[1].width - rect[2].width);
  1154. rect[3].bottom = 0;
  1155. rect[3].height = rect[0].height;
  1156. }
  1157. // modify UI
  1158. void UiModify(mjUI* ui, mjuiState* state, mjrContext* con) {
  1159. mjui_resize(ui, con);
  1160. // remake aux buffer only if missing or different
  1161. int id = ui->auxid;
  1162. if (con->auxFBO[id] == 0 ||
  1163. con->auxFBO_r[id] == 0 ||
  1164. con->auxColor[id] == 0 ||
  1165. con->auxColor_r[id] == 0 ||
  1166. con->auxWidth[id] != ui->width ||
  1167. con->auxHeight[id] != ui->maxheight ||
  1168. con->auxSamples[id] != ui->spacing.samples) {
  1169. mjr_addAux(id, ui->width, ui->maxheight, ui->spacing.samples, con);
  1170. }
  1171. UiLayout(state);
  1172. mjui_update(-1, -1, ui, state, con);
  1173. }
  1174. // handle UI event
  1175. void UiEvent(mjuiState* state) {
  1176. mj::Simulate* sim = static_cast<mj::Simulate*>(state->userdata);
  1177. // call UI 0 if event is directed to it
  1178. if ((state->dragrect==sim->ui0.rectid) ||
  1179. (state->dragrect==0 && state->mouserect==sim->ui0.rectid) ||
  1180. state->type==mjEVENT_KEY) {
  1181. // process UI event
  1182. mjuiItem* it = mjui_event(&sim->ui0, state, &sim->platform_ui->mjr_context());
  1183. // file section
  1184. if (it && it->sectionid==SECT_FILE) {
  1185. switch (it->itemid) {
  1186. case 0: // Save xml
  1187. sim->pending_.save_xml = GetSavePath("mjmodel.xml");
  1188. break;
  1189. case 1: // Save mjb
  1190. sim->pending_.save_mjb = GetSavePath("mjmodel.mjb");
  1191. break;
  1192. case 2: // Print model
  1193. sim->pending_.print_model = GetSavePath("MJMODEL.TXT");
  1194. break;
  1195. case 3: // Print data
  1196. sim->pending_.print_data = GetSavePath("MJDATA.TXT");
  1197. break;
  1198. case 4: // Quit
  1199. sim->exitrequest.store(1);
  1200. break;
  1201. case 5: // Screenshot
  1202. sim->screenshotrequest.store(true);
  1203. break;
  1204. }
  1205. }
  1206. // option section
  1207. else if (it && it->sectionid==SECT_OPTION) {
  1208. if (it->pdata == &sim->spacing) {
  1209. sim->ui0.spacing = mjui_themeSpacing(sim->spacing);
  1210. sim->ui1.spacing = mjui_themeSpacing(sim->spacing);
  1211. } else if (it->pdata == &sim->color) {
  1212. sim->ui0.color = mjui_themeColor(sim->color);
  1213. sim->ui1.color = mjui_themeColor(sim->color);
  1214. } else if (it->pdata == &sim->font) {
  1215. mjr_changeFont(50*(sim->font+1), &sim->platform_ui->mjr_context());
  1216. } else if (it->pdata == &sim->fullscreen) {
  1217. sim->platform_ui->ToggleFullscreen();
  1218. } else if (it->pdata == &sim->vsync) {
  1219. sim->platform_ui->SetVSync(sim->vsync);
  1220. }
  1221. // modify UI
  1222. UiModify(&sim->ui0, state, &sim->platform_ui->mjr_context());
  1223. UiModify(&sim->ui1, state, &sim->platform_ui->mjr_context());
  1224. }
  1225. // simulation section
  1226. else if (it && it->sectionid==SECT_SIMULATION) {
  1227. switch (it->itemid) {
  1228. case 1: // Reset
  1229. sim->pending_.reset = true;
  1230. break;
  1231. case 2: // Reload
  1232. sim->uiloadrequest.fetch_add(1);
  1233. break;
  1234. case 3: // Align
  1235. sim->pending_.align = true;
  1236. break;
  1237. case 4: // Copy pose
  1238. sim->pending_.copy_pose = true;
  1239. break;
  1240. case 5: // Adjust key
  1241. case 6: // Load key
  1242. sim->pending_.load_key = true;
  1243. break;
  1244. case 7: // Save key
  1245. sim->pending_.save_key = true;
  1246. break;
  1247. case 11: // History scrubber
  1248. sim->run = 0;
  1249. sim->pending_.load_from_history = true;
  1250. mjui0_update_section(sim, SECT_SIMULATION);
  1251. break;
  1252. }
  1253. }
  1254. // physics section
  1255. else if (it && it->sectionid==SECT_PHYSICS && sim->m_) {
  1256. mjOption* opt = sim->is_passive_ ? &sim->scnstate_.model.opt : &sim->m_->opt;
  1257. // update disable flags in mjOption
  1258. opt->disableflags = 0;
  1259. for (int i=0; i<mjNDISABLE; i++) {
  1260. if (sim->disable[i]) {
  1261. opt->disableflags |= (1<<i);
  1262. }
  1263. }
  1264. // update enable flags in mjOption
  1265. opt->enableflags = 0;
  1266. for (int i=0; i<mjNENABLE; i++) {
  1267. if (sim->enable[i]) {
  1268. opt->enableflags |= (1<<i);
  1269. }
  1270. }
  1271. // update disableactuator bitflag in mjOption
  1272. bool group_changed = false;
  1273. for (int i=0; i<mjNGROUP; i++) {
  1274. if ((!sim->enableactuator[i]) != (opt->disableactuator & (1<<i))) {
  1275. group_changed = true;
  1276. if (!sim->enableactuator[i]) {
  1277. // disable actuator group i
  1278. opt->disableactuator |= (1<<i);
  1279. } else {
  1280. // enable actuator group i
  1281. opt->disableactuator &= ~(1<<i);
  1282. }
  1283. }
  1284. }
  1285. // remake control section if actuator disable group changed
  1286. if (group_changed) {
  1287. sim->pending_.ui_remake_ctrl = true;
  1288. }
  1289. }
  1290. // rendering section
  1291. else if (it && it->sectionid==SECT_RENDERING) {
  1292. // set camera in mjvCamera
  1293. if (sim->camera==0) {
  1294. sim->cam.type = mjCAMERA_FREE;
  1295. } else if (sim->camera==1) {
  1296. if (sim->pert.select>0) {
  1297. sim->cam.type = mjCAMERA_TRACKING;
  1298. sim->cam.trackbodyid = sim->pert.select;
  1299. sim->cam.fixedcamid = -1;
  1300. } else {
  1301. sim->cam.type = mjCAMERA_FREE;
  1302. sim->camera = 0;
  1303. mjui0_update_section(sim, SECT_RENDERING);
  1304. }
  1305. } else {
  1306. sim->cam.type = mjCAMERA_FIXED;
  1307. sim->cam.fixedcamid = sim->camera - 2;
  1308. }
  1309. // copy camera spec to clipboard (as MJCF element)
  1310. if (it->itemid == 3) {
  1311. CopyCamera(sim);
  1312. }
  1313. }
  1314. // visualization section
  1315. else if (it && it->sectionid==SECT_VISUALIZATION) {
  1316. if (!mju::strcmp_arr(it->name, "Align")) {
  1317. sim->pending_.align = true;
  1318. }
  1319. }
  1320. // group section
  1321. else if (it && it->sectionid==SECT_GROUP) {
  1322. // remake joint section if joint group changed
  1323. if (it->name[0]=='J' && it->name[1]=='o') {
  1324. sim->ui1.nsect = SECT_JOINT;
  1325. MakeJointSection(sim);
  1326. sim->ui1.nsect = NSECT1;
  1327. UiModify(&sim->ui1, state, &sim->platform_ui->mjr_context());
  1328. }
  1329. // remake control section if actuator group changed
  1330. if (it->name[0]=='A' && it->name[1]=='c') {
  1331. sim->pending_.ui_remake_ctrl = true;
  1332. }
  1333. }
  1334. // stop if UI processed event
  1335. if (it!=nullptr || (state->type==mjEVENT_KEY && state->key==0)) {
  1336. return;
  1337. }
  1338. }
  1339. // call UI 1 if event is directed to it
  1340. if ((state->dragrect==sim->ui1.rectid) ||
  1341. (state->dragrect==0 && state->mouserect==sim->ui1.rectid) ||
  1342. state->type==mjEVENT_KEY) {
  1343. // process UI event
  1344. mjuiItem* it = mjui_event(&sim->ui1, state, &sim->platform_ui->mjr_context());
  1345. // control section
  1346. if (it && it->sectionid==SECT_CONTROL) {
  1347. // clear controls
  1348. if (it->itemid==0) {
  1349. sim->pending_.zero_ctrl = true;
  1350. }
  1351. }
  1352. // stop if UI processed event
  1353. if (it!=nullptr || (state->type==mjEVENT_KEY && state->key==0)) {
  1354. return;
  1355. }
  1356. }
  1357. // shortcut not handled by UI
  1358. if (state->type==mjEVENT_KEY && state->key!=0) {
  1359. switch (state->key) {
  1360. case ' ': // Mode
  1361. if (!sim->is_passive_ && sim->m_) {
  1362. sim->run = 1 - sim->run;
  1363. sim->pert.active = 0;
  1364. if (sim->run) sim->scrub_index = 0; // reset scrubber
  1365. mjui0_update_section(sim, -1);
  1366. }
  1367. break;
  1368. case mjKEY_RIGHT: // step forward
  1369. if (!sim->is_passive_ && sim->m_ && !sim->run) {
  1370. ClearTimers(sim->d_);
  1371. // currently in scrubber: increment scrub, load state, update slider UI
  1372. if (sim->scrub_index < 0) {
  1373. sim->scrub_index++;
  1374. sim->pending_.load_from_history = true;
  1375. mjui0_update_section(sim, SECT_SIMULATION);
  1376. }
  1377. // not in scrubber: step, add to history buffer
  1378. else {
  1379. mj_step(sim->m_, sim->d_);
  1380. sim->AddToHistory();
  1381. }
  1382. UpdateProfiler(sim, sim->m_, sim->d_);
  1383. UpdateSensor(sim, sim->m_, sim->d_);
  1384. UpdateSettings(sim, sim->m_);
  1385. }
  1386. break;
  1387. case mjKEY_LEFT: // step backward
  1388. if (!sim->is_passive_ && sim->m_) {
  1389. sim->run = 0;
  1390. ClearTimers(sim->d_);
  1391. // decrement scrub, load state
  1392. sim->scrub_index = mjMAX(sim->scrub_index - 1, 1 - sim->nhistory_);
  1393. sim->pending_.load_from_history = true;
  1394. // update slider UI, profiler, sensor
  1395. mjui0_update_section(sim, SECT_SIMULATION);
  1396. UpdateProfiler(sim, sim->m_, sim->d_);
  1397. UpdateSensor(sim, sim->m_, sim->d_);
  1398. }
  1399. break;
  1400. case mjKEY_PAGE_UP: // select parent body
  1401. if ((sim->m_ || sim->is_passive_) && sim->pert.select > 0) {
  1402. sim->pert.select = sim->body_parentid_[sim->pert.select];
  1403. sim->pert.flexselect = -1;
  1404. sim->pert.skinselect = -1;
  1405. // stop perturbation if world reached
  1406. if (sim->pert.select<=0) {
  1407. sim->pert.active = 0;
  1408. }
  1409. }
  1410. break;
  1411. case ']': // cycle up fixed cameras
  1412. if ((sim->m_ || !sim->is_passive_) && sim->ncam_) {
  1413. sim->cam.type = mjCAMERA_FIXED;
  1414. // camera = {0 or 1} are reserved for the free and tracking cameras
  1415. if (sim->camera < 2 || sim->camera == 2 + sim->ncam_ - 1) {
  1416. sim->camera = 2;
  1417. } else {
  1418. sim->camera += 1;
  1419. }
  1420. sim->cam.fixedcamid = sim->camera - 2;
  1421. mjui0_update_section(sim, SECT_RENDERING);
  1422. }
  1423. break;
  1424. case '[': // cycle down fixed cameras
  1425. if ((sim->m_ || sim->is_passive_) && sim->ncam_) {
  1426. sim->cam.type = mjCAMERA_FIXED;
  1427. // camera = {0 or 1} are reserved for the free and tracking cameras
  1428. if (sim->camera <= 2) {
  1429. sim->camera = 2 + sim->ncam_-1;
  1430. } else {
  1431. sim->camera -= 1;
  1432. }
  1433. sim->cam.fixedcamid = sim->camera - 2;
  1434. mjui0_update_section(sim, SECT_RENDERING);
  1435. }
  1436. break;
  1437. case mjKEY_F6: // cycle frame visualisation
  1438. if (sim->m_ || sim->is_passive_) {
  1439. sim->opt.frame = (sim->opt.frame + 1) % mjNFRAME;
  1440. mjui0_update_section(sim, SECT_RENDERING);
  1441. }
  1442. break;
  1443. case mjKEY_F7: // cycle label visualisation
  1444. if (sim->m_ || sim->is_passive_) {
  1445. sim->opt.label = (sim->opt.label + 1) % mjNLABEL;
  1446. mjui0_update_section(sim, SECT_RENDERING);
  1447. }
  1448. break;
  1449. case mjKEY_ESCAPE: // free camera
  1450. sim->cam.type = mjCAMERA_FREE;
  1451. sim->camera = 0;
  1452. mjui0_update_section(sim, SECT_RENDERING);
  1453. break;
  1454. case '-': // slow down
  1455. if (!sim->is_passive_) {
  1456. int numclicks = sizeof(sim->percentRealTime) / sizeof(sim->percentRealTime[0]);
  1457. if (sim->real_time_index < numclicks-1 && !state->shift) {
  1458. sim->real_time_index++;
  1459. sim->speed_changed = true;
  1460. }
  1461. }
  1462. break;
  1463. case '=': // speed up
  1464. if (!sim->is_passive_ && sim->real_time_index > 0 && !state->shift) {
  1465. sim->real_time_index--;
  1466. sim->speed_changed = true;
  1467. }
  1468. break;
  1469. case mjKEY_TAB: // toggle left/right UI
  1470. if (!state->shift) {
  1471. // toggle left UI
  1472. sim->ui0_enable = !sim->ui0_enable;
  1473. UiModify(&sim->ui0, state, &sim->platform_ui->mjr_context());
  1474. } else {
  1475. // toggle right UI
  1476. sim->ui1_enable = !sim->ui1_enable;
  1477. UiModify(&sim->ui1, state, &sim->platform_ui->mjr_context());
  1478. }
  1479. break;
  1480. }
  1481. return;
  1482. }
  1483. // 3D scroll
  1484. if (state->type==mjEVENT_SCROLL && state->mouserect==3) {
  1485. // emulate vertical mouse motion = 2% of window height
  1486. if (sim->m_ && !sim->is_passive_) {
  1487. mjv_moveCamera(sim->m_, mjMOUSE_ZOOM, 0, -zoom_increment*state->sy, &sim->scn, &sim->cam);
  1488. } else {
  1489. mjv_moveCameraFromState(
  1490. &sim->scnstate_, mjMOUSE_ZOOM, 0, -zoom_increment*state->sy, &sim->scn, &sim->cam);
  1491. }
  1492. return;
  1493. }
  1494. // 3D press
  1495. if (state->type==mjEVENT_PRESS && state->mouserect==3) {
  1496. // set perturbation
  1497. int newperturb = 0;
  1498. if (state->control && sim->pert.select>0 && (sim->m_ || sim->is_passive_)) {
  1499. // right: translate; left: rotate
  1500. if (state->right) {
  1501. newperturb = mjPERT_TRANSLATE;
  1502. } else if (state->left) {
  1503. newperturb = mjPERT_ROTATE;
  1504. }
  1505. if (newperturb && !sim->pert.active) {
  1506. sim->pending_.newperturb = newperturb;
  1507. }
  1508. }
  1509. // handle double-click
  1510. if (state->doubleclick && (sim->m_ || sim->is_passive_)) {
  1511. sim->pending_.select = true;
  1512. std::memcpy(&sim->pending_.select_state, state, sizeof(sim->pending_.select_state));
  1513. // stop perturbation on select
  1514. sim->pert.active = 0;
  1515. sim->pending_.newperturb = 0;
  1516. }
  1517. return;
  1518. }
  1519. // 3D release
  1520. if (state->type==mjEVENT_RELEASE && state->dragrect==3 && (sim->m_ || sim->is_passive_)) {
  1521. // stop perturbation
  1522. sim->pert.active = 0;
  1523. sim->pending_.newperturb = 0;
  1524. return;
  1525. }
  1526. // 3D move
  1527. if (state->type==mjEVENT_MOVE && state->dragrect==3 && (sim->m_ || sim->is_passive_)) {
  1528. // determine action based on mouse button
  1529. mjtMouse action;
  1530. if (state->right) {
  1531. action = state->shift ? mjMOUSE_MOVE_H : mjMOUSE_MOVE_V;
  1532. } else if (state->left) {
  1533. action = state->shift ? mjMOUSE_ROTATE_H : mjMOUSE_ROTATE_V;
  1534. } else {
  1535. action = mjMOUSE_ZOOM;
  1536. }
  1537. // move perturb or camera
  1538. mjrRect r = state->rect[3];
  1539. if (sim->pert.active) {
  1540. if (!sim->is_passive_) {
  1541. mjv_movePerturb(
  1542. sim->m_, sim->d_, action, state->dx / r.height, -state->dy / r.height,
  1543. &sim->scn, &sim->pert);
  1544. } else {
  1545. mjv_movePerturbFromState(
  1546. &sim->scnstate_, action, state->dx / r.height, -state->dy / r.height,
  1547. &sim->scn, &sim->pert);
  1548. }
  1549. } else {
  1550. if (!sim->is_passive_) {
  1551. mjv_moveCamera(
  1552. sim->m_, action, state->dx / r.height, -state->dy / r.height,
  1553. &sim->scn, &sim->cam);
  1554. } else {
  1555. mjv_moveCameraFromState(
  1556. &sim->scnstate_, action, state->dx / r.height, -state->dy / r.height,
  1557. &sim->scn, &sim->cam);
  1558. }
  1559. }
  1560. return;
  1561. }
  1562. // Dropped files
  1563. if (state->type == mjEVENT_FILESDROP && state->dropcount > 0 && !sim->is_passive_) {
  1564. while (sim->droploadrequest.load()) {}
  1565. mju::strcpy_arr(sim->dropfilename, state->droppaths[0]);
  1566. sim->droploadrequest.store(true);
  1567. return;
  1568. }
  1569. // Redraw
  1570. if (state->type == mjEVENT_REDRAW) {
  1571. sim->Render();
  1572. return;
  1573. }
  1574. }
  1575. } // namespace
  1576. namespace mujoco {
  1577. namespace mju = ::mujoco::sample_util;
  1578. Simulate::Simulate(std::unique_ptr<PlatformUIAdapter> platform_ui,
  1579. mjvCamera* cam, mjvOption* opt, mjvPerturb* pert,
  1580. bool is_passive)
  1581. : is_passive_(is_passive),
  1582. cam(*cam),
  1583. opt(*opt),
  1584. pert(*pert),
  1585. platform_ui(std::move(platform_ui)),
  1586. uistate(this->platform_ui->state()) {
  1587. mjv_defaultScene(&scn);
  1588. mjv_defaultSceneState(&scnstate_);
  1589. }
  1590. // synchronize model and data
  1591. // operations which require holding the mutex, prevents racing with physics thread
  1592. void Simulate::Sync() {
  1593. MutexLock lock(this->mtx);
  1594. if (!m_) {
  1595. return;
  1596. }
  1597. if (this->exitrequest.load()) {
  1598. return;
  1599. }
  1600. bool update_profiler = this->profiler && (this->pause_update || this->run);
  1601. bool update_sensor = this->sensor && (this->pause_update || this->run);
  1602. for (int i = 0; i < m_->njnt; ++i) {
  1603. std::optional<std::pair<mjtNum, mjtNum>> range;
  1604. if (m_->jnt_limited[i]) {
  1605. range.emplace(m_->jnt_range[2*i], m_->jnt_range[2*i + 1]);
  1606. }
  1607. if (jnt_range_[i] != range) {
  1608. pending_.ui_update_joint = true;
  1609. jnt_range_[i].swap(range);
  1610. }
  1611. }
  1612. for (int i = 0; i < m_->nu; ++i) {
  1613. std::optional<std::pair<mjtNum, mjtNum>> range;
  1614. if (m_->actuator_ctrllimited[i]) {
  1615. range.emplace(m_->actuator_ctrlrange[2*i], m_->actuator_ctrlrange[2*i + 1]);
  1616. }
  1617. if (actuator_ctrlrange_[i] != range) {
  1618. pending_.ui_remake_ctrl = true;
  1619. actuator_ctrlrange_[i].swap(range);
  1620. }
  1621. }
  1622. for (int i = 0; i < m_->nq; ++i) {
  1623. if (qpos_[i] != qpos_prev_[i]) {
  1624. d_->qpos[i] = qpos_[i];
  1625. } else {
  1626. qpos_[i] = d_->qpos[i];
  1627. }
  1628. if (qpos_prev_[i] != qpos_[i]) {
  1629. pending_.ui_update_joint = true;
  1630. qpos_prev_[i] = qpos_[i];
  1631. }
  1632. }
  1633. for (int i = 0; i < m_->nu; ++i) {
  1634. if (ctrl_[i] != ctrl_prev_[i]) {
  1635. d_->ctrl[i] = ctrl_[i];
  1636. } else {
  1637. ctrl_[i] = d_->ctrl[i];
  1638. }
  1639. if (ctrl_prev_[i] != ctrl_[i]) {
  1640. pending_.ui_update_ctrl = true;
  1641. ctrl_prev_[i] = ctrl_[i];
  1642. }
  1643. }
  1644. if (is_passive_) {
  1645. // synchronize m_->opt with changes made via the UI
  1646. #define X(name) \
  1647. if (IsDifferent(scnstate_.model.opt.name, mjopt_prev_.name)) { \
  1648. pending_.ui_update_physics = true; \
  1649. Copy(m_->opt.name, scnstate_.model.opt.name); \
  1650. }
  1651. X(timestep);
  1652. X(apirate);
  1653. X(impratio);
  1654. X(tolerance);
  1655. X(noslip_tolerance);
  1656. X(ccd_tolerance);
  1657. X(gravity);
  1658. X(wind);
  1659. X(magnetic);
  1660. X(density);
  1661. X(viscosity);
  1662. X(o_margin);
  1663. X(o_solref);
  1664. X(o_solimp);
  1665. X(o_friction);
  1666. X(integrator);
  1667. X(cone);
  1668. X(jacobian);
  1669. X(solver);
  1670. X(iterations);
  1671. X(noslip_iterations);
  1672. X(ccd_iterations);
  1673. X(disableflags);
  1674. X(enableflags);
  1675. X(disableactuator);
  1676. X(sdf_initpoints);
  1677. X(sdf_iterations);
  1678. #undef X
  1679. // synchronize number of mjWARN_VGEOMFULL warnings
  1680. if (scnstate_.data.warning[mjWARN_VGEOMFULL].number > warn_vgeomfull_prev_) {
  1681. d_->warning[mjWARN_VGEOMFULL].number +=
  1682. scnstate_.data.warning[mjWARN_VGEOMFULL].number - warn_vgeomfull_prev_;
  1683. }
  1684. }
  1685. if (pending_.save_xml) {
  1686. char err[200];
  1687. if (!pending_.save_xml->empty() && !mj_saveLastXML(pending_.save_xml->c_str(), m_, err, 200)) {
  1688. std::printf("Save XML error: %s", err);
  1689. }
  1690. pending_.save_xml = std::nullopt;
  1691. }
  1692. if (pending_.save_mjb) {
  1693. if (!pending_.save_mjb->empty()) {
  1694. mj_saveModel(m_, pending_.save_mjb->c_str(), nullptr, 0);
  1695. }
  1696. pending_.save_mjb = std::nullopt;
  1697. }
  1698. if (pending_.print_model) {
  1699. if (!pending_.print_model->empty()) {
  1700. mj_printModel(m_, pending_.print_model->c_str());
  1701. }
  1702. pending_.print_model = std::nullopt;
  1703. }
  1704. if (pending_.print_data) {
  1705. if (!pending_.print_data->empty()) {
  1706. mj_printData(m_, d_, pending_.print_data->c_str());
  1707. }
  1708. pending_.print_data = std::nullopt;
  1709. }
  1710. if (pending_.reset) {
  1711. mj_resetData(m_, d_);
  1712. mj_forward(m_, d_);
  1713. load_error[0] = '\0';
  1714. update_profiler = true;
  1715. update_sensor = true;
  1716. scrub_index = 0;
  1717. pending_.ui_update_simulation = true;
  1718. pending_.reset = false;
  1719. }
  1720. if (pending_.align) {
  1721. AlignAndScaleView(this, m_);
  1722. pending_.align = false;
  1723. }
  1724. if (pending_.copy_pose) {
  1725. CopyPose(this, m_, d_);
  1726. pending_.copy_pose = false;
  1727. }
  1728. if (pending_.load_from_history) {
  1729. LoadScrubState(this);
  1730. update_profiler = true;
  1731. update_sensor = true;
  1732. pending_.load_from_history = false;
  1733. }
  1734. if (pending_.load_key) {
  1735. mj_resetDataKeyframe(m_, d_, this->key);
  1736. mj_forward(m_, d_);
  1737. update_profiler = true;
  1738. update_sensor = true;
  1739. pending_.load_key = false;
  1740. }
  1741. if (pending_.save_key) {
  1742. mj_setKeyframe(m_, d_, this->key);
  1743. pending_.save_key = false;
  1744. }
  1745. if (pending_.zero_ctrl) {
  1746. mju_zero(d_->ctrl, m_->nu);
  1747. pending_.zero_ctrl = false;
  1748. }
  1749. // perturbation onset: reset reference
  1750. if (pending_.newperturb) {
  1751. mjv_initPerturb(m_, d_, &this->scn, &this->pert);
  1752. this->pert.active = pending_.newperturb;
  1753. pending_.newperturb = 0;
  1754. }
  1755. if (pending_.select) {
  1756. // determine selection mode
  1757. int selmode;
  1758. if (pending_.select_state.button==mjBUTTON_LEFT) {
  1759. selmode = 1;
  1760. } else if (pending_.select_state.control) {
  1761. selmode = 3;
  1762. } else {
  1763. selmode = 2;
  1764. }
  1765. // find geom and 3D click point, get corresponding body
  1766. mjrRect r = pending_.select_state.rect[3];
  1767. mjtNum selpnt[3];
  1768. int selgeom, selflex, selskin;
  1769. int selbody = mjv_select(m_, d_, &this->opt,
  1770. static_cast<mjtNum>(r.width) / r.height,
  1771. (pending_.select_state.x - r.left) / r.width,
  1772. (pending_.select_state.y - r.bottom) / r.height,
  1773. &this->scn, selpnt, &selgeom, &selflex, &selskin);
  1774. // set lookat point, start tracking is requested
  1775. if (selmode==2 || selmode==3) {
  1776. // copy selpnt if anything clicked
  1777. if (selbody>=0) {
  1778. mju_copy3(this->cam.lookat, selpnt);
  1779. }
  1780. // switch to tracking camera if dynamic body clicked
  1781. if (selmode==3 && selbody>0) {
  1782. // mujoco camera
  1783. this->cam.type = mjCAMERA_TRACKING;
  1784. this->cam.trackbodyid = selbody;
  1785. this->cam.fixedcamid = -1;
  1786. // UI camera
  1787. this->camera = 1;
  1788. pending_.ui_update_rendering = true;
  1789. }
  1790. }
  1791. // set body selection
  1792. else {
  1793. if (selbody>=0) {
  1794. // record selection
  1795. this->pert.select = selbody;
  1796. this->pert.flexselect = selflex;
  1797. this->pert.skinselect = selskin;
  1798. // compute localpos
  1799. mjtNum tmp[3];
  1800. mju_sub3(tmp, selpnt, d_->xpos + 3*this->pert.select);
  1801. mju_mulMatTVec(this->pert.localpos, d_->xmat + 9*this->pert.select, tmp, 3, 3);
  1802. } else {
  1803. this->pert.select = 0;
  1804. this->pert.flexselect = -1;
  1805. this->pert.skinselect = -1;
  1806. }
  1807. }
  1808. pending_.select = false;
  1809. }
  1810. // update scene
  1811. if (!is_passive_) {
  1812. mjv_updateScene(m_, d_, &this->opt, &this->pert, &this->cam, mjCAT_ALL, &this->scn);
  1813. } else {
  1814. mjv_updateSceneState(m_, d_, &this->opt, &scnstate_);
  1815. // append geoms from user_scn to scnstate_ scratch space
  1816. if (user_scn) {
  1817. int ngeom = user_scn->ngeom;
  1818. int maxgeom = scnstate_.scratch.maxgeom - scnstate_.scratch.ngeom;
  1819. if (ngeom > maxgeom) {
  1820. mj_warning(d_, mjWARN_VGEOMFULL, scnstate_.scratch.maxgeom);
  1821. ngeom = maxgeom;
  1822. }
  1823. if (ngeom > 0) {
  1824. std::memcpy(scnstate_.scratch.geoms + scnstate_.scratch.ngeom,
  1825. user_scn->geoms,
  1826. sizeof(mjvGeom) * ngeom);
  1827. scnstate_.scratch.ngeom += ngeom;
  1828. }
  1829. }
  1830. // pick up rendering flags changed via user_scn
  1831. if (user_scn) {
  1832. for (int i = 0; i < mjNRNDFLAG; ++i) {
  1833. if (user_scn->flags[i] != user_scn_flags_prev_[i]) {
  1834. scn.flags[i] = user_scn->flags[i];
  1835. pending_.ui_update_rendering = true;
  1836. }
  1837. }
  1838. Copy(user_scn->flags, scn.flags);
  1839. Copy(user_scn_flags_prev_, user_scn->flags);
  1840. }
  1841. mjopt_prev_ = scnstate_.model.opt;
  1842. warn_vgeomfull_prev_ = scnstate_.data.warning[mjWARN_VGEOMFULL].number;
  1843. }
  1844. // update settings
  1845. UpdateSettings(this, m_);
  1846. // update watch
  1847. if (this->ui0_enable && this->ui0.sect[SECT_WATCH].state) {
  1848. UpdateWatch(this, m_, d_);
  1849. }
  1850. // update info text
  1851. if (this->info) {
  1852. UpdateInfoText(this, m_, d_, this->info_title, this->info_content);
  1853. }
  1854. if (update_profiler) { UpdateProfiler(this, m_, d_); }
  1855. if (update_sensor) { UpdateSensor(this, m_, d_); }
  1856. // clear timers once profiler info has been copied
  1857. ClearTimers(d_);
  1858. if (this->run || this->is_passive_) {
  1859. // clear old perturbations, apply new
  1860. mju_zero(d_->xfrc_applied, 6*m_->nbody);
  1861. mjv_applyPerturbPose(m_, d_, &this->pert, 0); // mocap bodies only
  1862. mjv_applyPerturbForce(m_, d_, &this->pert);
  1863. } else {
  1864. mjv_applyPerturbPose(m_, d_, &this->pert, 1); // mocap and dynamic bodies
  1865. }
  1866. }
  1867. //------------------------- Tell the render thread to load a file and wait -------------------------
  1868. void Simulate::LoadMessage(const char* displayed_filename) {
  1869. mju::strcpy_arr(this->filename, displayed_filename);
  1870. {
  1871. MutexLock lock(mtx);
  1872. this->loadrequest = 3;
  1873. }
  1874. }
  1875. void Simulate::Load(mjModel* m, mjData* d, const char* displayed_filename) {
  1876. this->mnew_ = m;
  1877. this->dnew_ = d;
  1878. mju::strcpy_arr(this->filename, displayed_filename);
  1879. {
  1880. MutexLock lock(mtx);
  1881. this->loadrequest = 2;
  1882. // Wait for the render thread to be done loading
  1883. // so that we know the old model and data's memory can
  1884. // be free'd by the other thread (sometimes python)
  1885. cond_loadrequest.wait(lock, [this]() { return this->loadrequest == 0; });
  1886. }
  1887. }
  1888. void Simulate::LoadMessageClear(void) {
  1889. {
  1890. MutexLock lock(mtx);
  1891. this->loadrequest = 0;
  1892. }
  1893. }
  1894. //------------------------------------- load mjb or xml model --------------------------------------
  1895. void Simulate::LoadOnRenderThread() {
  1896. this->m_ = this->mnew_;
  1897. this->d_ = this->dnew_;
  1898. ncam_ = this->m_->ncam;
  1899. nkey_ = this->m_->nkey;
  1900. body_parentid_.resize(this->m_->nbody);
  1901. std::memcpy(body_parentid_.data(), this->m_->body_parentid,
  1902. sizeof(this->m_->body_parentid[0]) * this->m_->nbody);
  1903. jnt_type_.resize(this->m_->njnt);
  1904. std::memcpy(jnt_type_.data(), this->m_->jnt_type,
  1905. sizeof(this->m_->jnt_type[0]) * this->m_->njnt);
  1906. jnt_group_.resize(this->m_->njnt);
  1907. std::memcpy(jnt_group_.data(), this->m_->jnt_group,
  1908. sizeof(this->m_->jnt_group[0]) * this->m_->njnt);
  1909. jnt_qposadr_.resize(this->m_->njnt);
  1910. std::memcpy(jnt_qposadr_.data(), this->m_->jnt_qposadr,
  1911. sizeof(this->m_->jnt_qposadr[0]) * this->m_->njnt);
  1912. jnt_range_.clear();
  1913. jnt_range_.reserve(this->m_->njnt);
  1914. for (int i = 0; i < this->m_->njnt; ++i) {
  1915. if (this->m_->jnt_limited[i]) {
  1916. jnt_range_.push_back(
  1917. std::make_pair(this->m_->jnt_range[2 * i], this->m_->jnt_range[2 * i + 1]));
  1918. } else {
  1919. jnt_range_.push_back(std::nullopt);
  1920. }
  1921. }
  1922. jnt_names_.clear();
  1923. jnt_names_.reserve(this->m_->njnt);
  1924. for (int i = 0; i < this->m_->njnt; ++i) {
  1925. jnt_names_.emplace_back(this->m_->names + this->m_->name_jntadr[i]);
  1926. }
  1927. actuator_group_.resize(this->m_->nu);
  1928. std::memcpy(actuator_group_.data(), this->m_->actuator_group,
  1929. sizeof(this->m_->actuator_group[0]) * this->m_->nu);
  1930. actuator_ctrlrange_.clear();
  1931. actuator_ctrlrange_.reserve(this->m_->nu);
  1932. for (int i = 0; i < this->m_->nu; ++i) {
  1933. if (this->m_->actuator_ctrllimited[i]) {
  1934. actuator_ctrlrange_.push_back(std::make_pair(
  1935. this->m_->actuator_ctrlrange[2 * i], this->m_->actuator_ctrlrange[2 * i + 1]));
  1936. } else {
  1937. actuator_ctrlrange_.push_back(std::nullopt);
  1938. }
  1939. }
  1940. actuator_names_.clear();
  1941. actuator_names_.reserve(this->m_->nu);
  1942. for (int i = 0; i < this->m_->nu; ++i) {
  1943. actuator_names_.emplace_back(this->m_->names + this->m_->name_actuatoradr[i]);
  1944. }
  1945. qpos_.resize(this->m_->nq);
  1946. std::memcpy(qpos_.data(), this->d_->qpos, sizeof(this->d_->qpos[0]) * this->m_->nq);
  1947. qpos_prev_ = qpos_;
  1948. ctrl_.resize(this->m_->nu);
  1949. std::memcpy(ctrl_.data(), this->d_->ctrl, sizeof(this->d_->ctrl[0]) * this->m_->nu);
  1950. ctrl_prev_ = ctrl_;
  1951. // allocate history buffer: smaller of {2000 states, 100 MB}
  1952. if (!this->is_passive_) {
  1953. constexpr int kMaxHistoryBytes = 1e8;
  1954. // get state size, size of history buffer
  1955. state_size_ = mj_stateSize(this->m_, mjSTATE_INTEGRATION);
  1956. int state_bytes = state_size_ * sizeof(mjtNum);
  1957. int history_length = mjMIN(INT_MAX / state_bytes, 2000);
  1958. int history_bytes = mjMIN(state_bytes * history_length, kMaxHistoryBytes);
  1959. nhistory_ = history_bytes / state_bytes;
  1960. // allocate history buffer, reset cursor and UI slider
  1961. history_.clear();
  1962. history_.resize(nhistory_ * state_size_);
  1963. history_cursor_ = 0;
  1964. scrub_index = 0;
  1965. // fill buffer with initial state
  1966. mj_getState(this->m_, this->d_, history_.data(), mjSTATE_INTEGRATION);
  1967. for (int i = 1; i < nhistory_; ++i) {
  1968. mju_copy(&history_[i * state_size_], history_.data(), state_size_);
  1969. }
  1970. }
  1971. // re-create scene and context
  1972. mjv_makeScene(this->m_, &this->scn, kMaxGeom);
  1973. if (this->is_passive_) {
  1974. mjopt_prev_ = m_->opt;
  1975. opt_prev_ = opt;
  1976. cam_prev_ = cam;
  1977. warn_vgeomfull_prev_ = d_->warning[mjWARN_VGEOMFULL].number;
  1978. mjv_makeSceneState(this->m_, this->d_, &this->scnstate_, kMaxGeom);
  1979. }
  1980. this->platform_ui->RefreshMjrContext(this->m_, 50*(this->font+1));
  1981. UiModify(&this->ui0, &this->uistate, &this->platform_ui->mjr_context());
  1982. UiModify(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  1983. if (!this->platform_ui->IsGPUAccelerated()) {
  1984. this->scn.flags[mjRND_SHADOW] = 0;
  1985. this->scn.flags[mjRND_REFLECTION] = 0;
  1986. }
  1987. if (this->user_scn) {
  1988. Copy(this->user_scn->flags, this->scn.flags);
  1989. Copy(this->user_scn_flags_prev_, this->scn.flags);
  1990. }
  1991. // clear perturbation state
  1992. this->pert.active = 0;
  1993. this->pert.select = 0;
  1994. this->pert.flexselect = -1;
  1995. this->pert.skinselect = -1;
  1996. // align and scale view unless reloading the same file
  1997. if (this->filename[0] &&
  1998. mju::strcmp_arr(this->filename, this->previous_filename)) {
  1999. AlignAndScaleView(this, this->m_);
  2000. mju::strcpy_arr(this->previous_filename, this->filename);
  2001. }
  2002. // update scene
  2003. if (!is_passive_) {
  2004. mjv_updateScene(this->m_, this->d_,
  2005. &this->opt, &this->pert, &this->cam, mjCAT_ALL, &this->scn);
  2006. } else {
  2007. mjv_updateSceneState(this->m_, this->d_, &this->opt, &this->scnstate_);
  2008. }
  2009. // set window title to model name
  2010. if (this->m_->names) {
  2011. char title[200] = "MuJoCo : ";
  2012. mju::strcat_arr(title, this->m_->names);
  2013. platform_ui->SetWindowTitle(title);
  2014. }
  2015. // set keyframe range and divisions
  2016. this->ui0.sect[SECT_SIMULATION].item[5].slider.range[0] = 0;
  2017. this->ui0.sect[SECT_SIMULATION].item[5].slider.range[1] = mjMAX(0, this->m_->nkey - 1);
  2018. this->ui0.sect[SECT_SIMULATION].item[5].slider.divisions = mjMAX(1, this->m_->nkey - 1);
  2019. // set scrubber range and divisions
  2020. this->ui0.sect[SECT_SIMULATION].item[11].slider.range[0] = 1 - nhistory_;
  2021. this->ui0.sect[SECT_SIMULATION].item[11].slider.divisions = nhistory_;
  2022. // rebuild UI sections
  2023. MakeUiSections(this, this->m_, this->d_);
  2024. // full ui update
  2025. UiModify(&this->ui0, &this->uistate, &this->platform_ui->mjr_context());
  2026. UiModify(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2027. UpdateSettings(this, this->m_);
  2028. // clear request
  2029. this->loadrequest = 0;
  2030. cond_loadrequest.notify_all();
  2031. // set real time index
  2032. int numclicks = sizeof(this->percentRealTime) / sizeof(this->percentRealTime[0]);
  2033. float min_error = 1e6;
  2034. float desired = mju_log(100*this->m_->vis.global.realtime);
  2035. for (int click=0; click<numclicks; click++) {
  2036. float error = mju_abs(mju_log(this->percentRealTime[click]) - desired);
  2037. if (error < min_error) {
  2038. min_error = error;
  2039. this->real_time_index = click;
  2040. }
  2041. }
  2042. this->mnew_ = nullptr;
  2043. this->dnew_ = nullptr;
  2044. }
  2045. //------------------------------------------- rendering --------------------------------------------
  2046. // render the ui to the window
  2047. void Simulate::Render() {
  2048. // update rendering context buffer size if required
  2049. if (this->platform_ui->EnsureContextSize()) {
  2050. UiModify(&this->ui0, &this->uistate, &this->platform_ui->mjr_context());
  2051. UiModify(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2052. }
  2053. // get 3D rectangle and reduced for profiler
  2054. mjrRect rect = this->uistate.rect[3];
  2055. mjrRect smallrect = rect;
  2056. if (this->profiler) {
  2057. smallrect.width = rect.width - rect.width/4;
  2058. }
  2059. // no model
  2060. if (!this->is_passive_ && !this->m_) {
  2061. // blank screen
  2062. mjr_rectangle(rect, 0.2f, 0.3f, 0.4f, 1);
  2063. // label
  2064. if (this->loadrequest) {
  2065. mjr_overlay(mjFONT_BIG, mjGRID_TOP, smallrect, "LOADING...", nullptr,
  2066. &this->platform_ui->mjr_context());
  2067. } else {
  2068. char intro_message[Simulate::kMaxFilenameLength];
  2069. mju::sprintf_arr(intro_message,
  2070. "MuJoCo version %s\nDrag-and-drop model file here", mj_versionString());
  2071. mjr_overlay(mjFONT_NORMAL, mjGRID_TOPLEFT, rect, intro_message, 0,
  2072. &this->platform_ui->mjr_context());
  2073. }
  2074. // show last loading error
  2075. if (this->load_error[0]) {
  2076. mjr_overlay(mjFONT_NORMAL, mjGRID_BOTTOMLEFT, rect, this->load_error, 0,
  2077. &this->platform_ui->mjr_context());
  2078. }
  2079. // render uis
  2080. if (this->ui0_enable) {
  2081. mjui_render(&this->ui0, &this->uistate, &this->platform_ui->mjr_context());
  2082. }
  2083. if (this->ui1_enable) {
  2084. mjui_render(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2085. }
  2086. // finalize
  2087. this->platform_ui->SwapBuffers();
  2088. return;
  2089. }
  2090. // update UI sections from last sync
  2091. if (pending_.ui_update_simulation) {
  2092. if (this->ui0_enable && this->ui0.sect[SECT_SIMULATION].state) {
  2093. mjui0_update_section(this, SECT_SIMULATION);
  2094. }
  2095. pending_.ui_update_simulation = false;
  2096. }
  2097. if (this->ui0_enable && this->ui0.sect[SECT_WATCH].state) {
  2098. mjui0_update_section(this, SECT_WATCH);
  2099. }
  2100. if (pending_.ui_update_physics) {
  2101. if (this->ui0_enable && this->ui0.sect[SECT_PHYSICS].state) {
  2102. mjui0_update_section(this, SECT_PHYSICS);
  2103. }
  2104. pending_.ui_update_physics = false;
  2105. }
  2106. if (is_passive_) {
  2107. if (this->ui0_enable && this->ui0.sect[SECT_RENDERING].state &&
  2108. (cam_prev_.type != cam.type ||
  2109. cam_prev_.fixedcamid != cam.fixedcamid ||
  2110. cam_prev_.trackbodyid != cam.trackbodyid ||
  2111. opt_prev_.label != opt.label || opt_prev_.frame != opt.frame ||
  2112. IsDifferent(opt_prev_.flags, opt.flags))) {
  2113. pending_.ui_update_rendering = true;
  2114. }
  2115. if (this->ui0_enable && this->ui0.sect[SECT_RENDERING].state &&
  2116. (IsDifferent(opt_prev_.geomgroup, opt.geomgroup) ||
  2117. IsDifferent(opt_prev_.sitegroup, opt.sitegroup) ||
  2118. IsDifferent(opt_prev_.jointgroup, opt.jointgroup) ||
  2119. IsDifferent(opt_prev_.tendongroup, opt.tendongroup) ||
  2120. IsDifferent(opt_prev_.actuatorgroup, opt.actuatorgroup) ||
  2121. IsDifferent(opt_prev_.flexgroup, opt.flexgroup) ||
  2122. IsDifferent(opt_prev_.skingroup, opt.skingroup))) {
  2123. mjui0_update_section(this, SECT_GROUP);
  2124. }
  2125. opt_prev_ = opt;
  2126. cam_prev_ = cam;
  2127. }
  2128. if (pending_.ui_update_rendering) {
  2129. if (this->ui0_enable && this->ui0.sect[SECT_RENDERING].state) {
  2130. mjui0_update_section(this, SECT_RENDERING);
  2131. }
  2132. pending_.ui_update_rendering = false;
  2133. }
  2134. if (pending_.ui_update_joint) {
  2135. if (this->ui1_enable && this->ui1.sect[SECT_JOINT].state) {
  2136. mjui_update(SECT_JOINT, -1, &this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2137. }
  2138. pending_.ui_update_joint = false;
  2139. }
  2140. if (pending_.ui_remake_ctrl) {
  2141. if (this->ui1_enable && this->ui1.sect[SECT_CONTROL].state) {
  2142. this->ui1.nsect = SECT_CONTROL;
  2143. MakeControlSection(this);
  2144. this->ui1.nsect = NSECT1;
  2145. UiModify(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2146. }
  2147. pending_.ui_remake_ctrl = false;
  2148. }
  2149. if (pending_.ui_update_ctrl) {
  2150. if (this->ui1_enable && this->ui1.sect[SECT_CONTROL].state) {
  2151. mjui_update(SECT_CONTROL, -1, &this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2152. }
  2153. pending_.ui_update_ctrl = false;
  2154. }
  2155. // render scene
  2156. mjr_render(rect, &this->scn, &this->platform_ui->mjr_context());
  2157. // show last loading error
  2158. if (this->load_error[0]) {
  2159. mjr_overlay(mjFONT_NORMAL, mjGRID_BOTTOMLEFT, rect, this->load_error, 0,
  2160. &this->platform_ui->mjr_context());
  2161. }
  2162. // show pause/loading label
  2163. if (!this->run || this->loadrequest) {
  2164. char label[30] = {'\0'};
  2165. if (this->loadrequest) {
  2166. std::snprintf(label, sizeof(label), "LOADING...");
  2167. } else if (this->scrub_index == 0) {
  2168. std::snprintf(label, sizeof(label), "PAUSE");
  2169. } else {
  2170. std::snprintf(label, sizeof(label), "PAUSE (%d)", this->scrub_index);
  2171. }
  2172. mjr_overlay(mjFONT_BIG, mjGRID_TOP, smallrect, label, nullptr,
  2173. &this->platform_ui->mjr_context());
  2174. }
  2175. // get desired and actual percent-of-real-time
  2176. float desiredRealtime = this->percentRealTime[this->real_time_index];
  2177. float actualRealtime = 100 / this->measured_slowdown;
  2178. // if running, check for misalignment of more than 10%
  2179. float realtime_offset = mju_abs(actualRealtime - desiredRealtime);
  2180. bool misaligned = this->run && realtime_offset > 0.1 * desiredRealtime;
  2181. // make realtime overlay label
  2182. char rtlabel[30] = {'\0'};
  2183. if (desiredRealtime != 100.0 || misaligned) {
  2184. // print desired realtime
  2185. int labelsize = std::snprintf(rtlabel, sizeof(rtlabel), "%g%%", desiredRealtime);
  2186. // if misaligned, append to label
  2187. if (misaligned) {
  2188. std::snprintf(rtlabel+labelsize, sizeof(rtlabel)-labelsize, " (%-4.1f%%)", actualRealtime);
  2189. }
  2190. }
  2191. // show real-time overlay
  2192. if (rtlabel[0]) {
  2193. mjr_overlay(mjFONT_BIG, mjGRID_TOPLEFT, smallrect, rtlabel, nullptr,
  2194. &this->platform_ui->mjr_context());
  2195. }
  2196. // show ui 0
  2197. if (this->ui0_enable) {
  2198. mjui_render(&this->ui0, &this->uistate, &this->platform_ui->mjr_context());
  2199. }
  2200. // show ui 1
  2201. if (this->ui1_enable) {
  2202. mjui_render(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2203. }
  2204. // show help
  2205. if (this->help) {
  2206. mjr_overlay(mjFONT_NORMAL, mjGRID_TOPLEFT, rect, help_title, help_content,
  2207. &this->platform_ui->mjr_context());
  2208. }
  2209. // show info
  2210. if (this->info) {
  2211. mjr_overlay(mjFONT_NORMAL, mjGRID_BOTTOMLEFT, rect, this->info_title, this->info_content,
  2212. &this->platform_ui->mjr_context());
  2213. }
  2214. // show profiler
  2215. if (this->profiler) {
  2216. ShowProfiler(this, rect);
  2217. }
  2218. // show sensor
  2219. if (this->sensor) {
  2220. ShowSensor(this, smallrect);
  2221. }
  2222. // take screenshot, save to file
  2223. if (this->screenshotrequest.exchange(false)) {
  2224. const unsigned int h = uistate.rect[0].height;
  2225. const unsigned int w = uistate.rect[0].width;
  2226. std::unique_ptr<unsigned char[]> rgb(new unsigned char[3*w*h]);
  2227. if (!rgb) {
  2228. mju_error("could not allocate buffer for screenshot");
  2229. }
  2230. mjr_readPixels(rgb.get(), nullptr, uistate.rect[0], &this->platform_ui->mjr_context());
  2231. // flip up-down
  2232. for (int r = 0; r < h/2; ++r) {
  2233. unsigned char* top_row = &rgb[3*w*r];
  2234. unsigned char* bottom_row = &rgb[3*w*(h-1-r)];
  2235. std::swap_ranges(top_row, top_row+3*w, bottom_row);
  2236. }
  2237. // save as PNG
  2238. // TODO(b/241577466): Parse the stem of the filename and use a .PNG extension.
  2239. // Unfortunately, if we just yank ".xml"/".mjb" from the filename and append .PNG, the macOS
  2240. // file dialog does not automatically open that location. Thus, we defer to a default
  2241. // "screenshot.png" for now.
  2242. const std::string path = GetSavePath("screenshot.png");
  2243. if (!path.empty()) {
  2244. if (lodepng::encode(path, rgb.get(), w, h, LCT_RGB)) {
  2245. mju_error("could not save screenshot");
  2246. } else {
  2247. std::printf("saved screenshot: %s\n", path.c_str());
  2248. }
  2249. }
  2250. }
  2251. // finalize
  2252. this->platform_ui->SwapBuffers();
  2253. }
  2254. void Simulate::RenderLoop() {
  2255. // Set timer callback (milliseconds)
  2256. mjcb_time = Timer;
  2257. // init abstract visualization
  2258. mjv_defaultCamera(&this->cam);
  2259. mjv_defaultOption(&this->opt);
  2260. InitializeProfiler(this);
  2261. InitializeSensor(this);
  2262. // make empty scene
  2263. if (!is_passive_) {
  2264. mjv_defaultScene(&this->scn);
  2265. mjv_makeScene(nullptr, &this->scn, kMaxGeom);
  2266. }
  2267. if (!this->platform_ui->IsGPUAccelerated()) {
  2268. this->scn.flags[mjRND_SHADOW] = 0;
  2269. this->scn.flags[mjRND_REFLECTION] = 0;
  2270. }
  2271. // select default font
  2272. int fontscale = ComputeFontScale(*this->platform_ui);
  2273. this->font = fontscale/50 - 1;
  2274. // make empty context
  2275. this->platform_ui->RefreshMjrContext(nullptr, fontscale);
  2276. // init state and uis
  2277. std::memset(&this->uistate, 0, sizeof(mjuiState));
  2278. std::memset(&this->ui0, 0, sizeof(mjUI));
  2279. std::memset(&this->ui1, 0, sizeof(mjUI));
  2280. auto [buf_width, buf_height] = this->platform_ui->GetFramebufferSize();
  2281. this->uistate.nrect = 1;
  2282. this->uistate.rect[0].width = buf_width;
  2283. this->uistate.rect[0].height = buf_height;
  2284. this->ui0.spacing = mjui_themeSpacing(this->spacing);
  2285. this->ui0.color = mjui_themeColor(this->color);
  2286. this->ui0.predicate = UiPredicate;
  2287. this->ui0.rectid = 1;
  2288. this->ui0.auxid = 0;
  2289. this->ui1.spacing = mjui_themeSpacing(this->spacing);
  2290. this->ui1.color = mjui_themeColor(this->color);
  2291. this->ui1.predicate = UiPredicate;
  2292. this->ui1.rectid = 2;
  2293. this->ui1.auxid = 1;
  2294. // set GUI adapter callbacks
  2295. this->uistate.userdata = this;
  2296. this->platform_ui->SetEventCallback(UiEvent);
  2297. this->platform_ui->SetLayoutCallback(UiLayout);
  2298. // populate uis with standard sections, open some sections initially
  2299. this->ui0.userdata = this;
  2300. this->ui1.userdata = this;
  2301. mjui_add(&this->ui0, defFile);
  2302. mjui_add(&this->ui0, this->def_option);
  2303. mjui_add(&this->ui0, this->def_simulation);
  2304. this->ui0.sect[0].state = 1;
  2305. this->ui0.sect[1].state = 1;
  2306. this->ui0.sect[2].state = 1;
  2307. mjui_add(&this->ui0, this->def_watch);
  2308. UiModify(&this->ui0, &this->uistate, &this->platform_ui->mjr_context());
  2309. UiModify(&this->ui1, &this->uistate, &this->platform_ui->mjr_context());
  2310. // set VSync to initial value
  2311. this->platform_ui->SetVSync(this->vsync);
  2312. frames_ = 0;
  2313. last_fps_update_ = mj::Simulate::Clock::now();
  2314. // run event loop
  2315. while (!this->platform_ui->ShouldCloseWindow() && !this->exitrequest.load()) {
  2316. {
  2317. const MutexLock lock(this->mtx);
  2318. // load model (not on first pass, to show "loading" label)
  2319. if (this->loadrequest==1) {
  2320. this->LoadOnRenderThread();
  2321. } else if (this->loadrequest == 2) {
  2322. this->loadrequest = 1;
  2323. }
  2324. // poll and handle events
  2325. this->platform_ui->PollEvents();
  2326. // upload assets if requested
  2327. bool upload_notify = false;
  2328. if (hfield_upload_ != -1) {
  2329. mjr_uploadHField(m_, &platform_ui->mjr_context(), hfield_upload_);
  2330. hfield_upload_ = -1;
  2331. upload_notify = true;
  2332. }
  2333. if (mesh_upload_ != -1) {
  2334. mjr_uploadMesh(m_, &platform_ui->mjr_context(), mesh_upload_);
  2335. mesh_upload_ = -1;
  2336. upload_notify = true;
  2337. }
  2338. if (texture_upload_ != -1) {
  2339. mjr_uploadTexture(m_, &platform_ui->mjr_context(), texture_upload_);
  2340. texture_upload_ = -1;
  2341. upload_notify = true;
  2342. }
  2343. if (upload_notify) {
  2344. cond_upload_.notify_all();
  2345. }
  2346. // update scene, doing a full sync if in fully managed mode
  2347. if (!this->is_passive_) {
  2348. Sync();
  2349. } else {
  2350. scnstate_.data.warning[mjWARN_VGEOMFULL].number += mjv_updateSceneFromState(
  2351. &scnstate_, &this->opt, &this->pert, &this->cam, mjCAT_ALL, &this->scn);
  2352. }
  2353. } // MutexLock (unblocks simulation thread)
  2354. // render while simulation is running
  2355. this->Render();
  2356. // update FPS stat, at most 5 times per second
  2357. auto now = mj::Simulate::Clock::now();
  2358. double interval = Seconds(now - last_fps_update_).count();
  2359. ++frames_;
  2360. if (interval > 0.2) {
  2361. last_fps_update_ = now;
  2362. fps_ = frames_ / interval;
  2363. frames_ = 0;
  2364. }
  2365. }
  2366. const MutexLock lock(this->mtx);
  2367. mjv_freeScene(&this->scn);
  2368. if (is_passive_) {
  2369. mjv_freeSceneState(&scnstate_);
  2370. }
  2371. this->exitrequest.store(2);
  2372. }
  2373. // add state to history buffer
  2374. void Simulate::AddToHistory() {
  2375. if (history_.empty()) {
  2376. return;
  2377. }
  2378. // circular increment of cursor
  2379. history_cursor_ = (history_cursor_ + 1) % nhistory_;
  2380. // add state at cursor
  2381. mjtNum* state = &history_[state_size_ * history_cursor_];
  2382. mj_getState(m_, d_, state, mjSTATE_INTEGRATION);
  2383. }
  2384. // inject Brownian noise
  2385. void Simulate::InjectNoise() {
  2386. // no noise, return
  2387. if (ctrl_noise_std <= 0) {
  2388. return;
  2389. }
  2390. // convert rate and scale to discrete time (Ornstein–Uhlenbeck)
  2391. mjtNum rate = mju_exp(-m_->opt.timestep / ctrl_noise_rate);
  2392. mjtNum scale = ctrl_noise_std * mju_sqrt(1-rate*rate);
  2393. for (int i=0; i<m_->nu; i++) {
  2394. mjtNum bottom = 0, top = 0, midpoint = 0, halfrange = 1;
  2395. if (m_->actuator_ctrllimited[i]) {
  2396. bottom = m_->actuator_ctrlrange[2*i];
  2397. top = m_->actuator_ctrlrange[2*i+1];
  2398. midpoint = 0.5 * (top + bottom); // target of exponential decay
  2399. halfrange = 0.5 * (top - bottom); // scales noise
  2400. }
  2401. // exponential convergence to midpoint at ctrl_noise_rate
  2402. d_->ctrl[i] = rate * d_->ctrl[i] + (1-rate) * midpoint;
  2403. // add noise
  2404. d_->ctrl[i] += scale * halfrange * mju_standardNormal(nullptr);
  2405. // clip to range if limited
  2406. if (m_->actuator_ctrllimited[i]) {
  2407. d_->ctrl[i] = mju_clip(d_->ctrl[i], bottom, top);
  2408. }
  2409. }
  2410. }
  2411. void Simulate::UpdateHField(int hfieldid) {
  2412. MutexLock lock(this->mtx);
  2413. if (!m_ || hfieldid < 0 || hfieldid >= m_->nhfield) {
  2414. return;
  2415. }
  2416. hfield_upload_ = hfieldid;
  2417. cond_upload_.wait(lock, [this]() { return hfield_upload_ == -1; });
  2418. }
  2419. void Simulate::UpdateMesh(int meshid) {
  2420. MutexLock lock(this->mtx);
  2421. if (!m_ || meshid < 0 || meshid >= m_->nmesh) {
  2422. return;
  2423. }
  2424. mesh_upload_ = meshid;
  2425. cond_upload_.wait(lock, [this]() { return mesh_upload_ == -1; });
  2426. }
  2427. void Simulate::UpdateTexture(int texid) {
  2428. MutexLock lock(this->mtx);
  2429. if (!m_ || texid < 0 || texid >= m_->ntex) {
  2430. return;
  2431. }
  2432. texture_upload_ = texid;
  2433. cond_upload_.wait(lock, [this]() { return texture_upload_ == -1; });
  2434. }
  2435. } // namespace mujoco