simulate.h 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328
  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. #ifndef MUJOCO_SIMULATE_SIMULATE_H_
  15. #define MUJOCO_SIMULATE_SIMULATE_H_
  16. #include <atomic>
  17. #include <chrono>
  18. #include <condition_variable>
  19. #include <memory>
  20. #include <mutex>
  21. #include <optional>
  22. #include <ratio>
  23. #include <string>
  24. #include <utility>
  25. #include <vector>
  26. #include <mujoco/mjui.h>
  27. #include <mujoco/mujoco.h>
  28. #include "platform_ui_adapter.h"
  29. namespace mujoco {
  30. // The viewer itself doesn't require a reentrant mutex, however we use it in
  31. // order to provide a Python sync API that doesn't require separate locking
  32. // (since sync is by far the most common operation), but that also won't
  33. // deadlock if called when a lock is already held by the user script on the
  34. // same thread.
  35. class SimulateMutex : public std::recursive_mutex {};
  36. using MutexLock = std::unique_lock<std::recursive_mutex>;
  37. // Simulate states not contained in MuJoCo structures
  38. class Simulate {
  39. public:
  40. using Clock = std::chrono::steady_clock;
  41. static_assert(std::ratio_less_equal_v<Clock::period, std::milli>);
  42. static constexpr int kMaxGeom = 20000;
  43. // create object and initialize the simulate ui
  44. Simulate(
  45. std::unique_ptr<PlatformUIAdapter> platform_ui_adapter,
  46. mjvCamera* cam, mjvOption* opt, mjvPerturb* pert, bool is_passive);
  47. // Synchronize mjModel and mjData state with UI inputs, and update
  48. // visualization.
  49. void Sync();
  50. void UpdateHField(int hfieldid);
  51. void UpdateMesh(int meshid);
  52. void UpdateTexture(int texid);
  53. // Request that the Simulate UI display a "loading" message
  54. // Called prior to Load or LoadMessageClear
  55. void LoadMessage(const char* displayed_filename);
  56. // Request that the Simulate UI thread render a new model
  57. void Load(mjModel* m, mjData* d, const char* displayed_filename);
  58. // Clear the loading message
  59. // Can be called instead of Load to clear the message without
  60. // requesting the UI load a model
  61. void LoadMessageClear(void);
  62. // functions below are used by the renderthread
  63. // load mjb or xml model that has been requested by load()
  64. void LoadOnRenderThread();
  65. // render the ui to the window
  66. void Render();
  67. // loop to render the UI (must be called from main thread because of MacOS)
  68. void RenderLoop();
  69. // add state to history buffer
  70. void AddToHistory();
  71. // inject control noise
  72. void InjectNoise();
  73. // constants
  74. static constexpr int kMaxFilenameLength = 1000;
  75. // whether the viewer is operating in passive mode, where it cannot assume
  76. // that it has exclusive access to mjModel, mjData, and various mjv objects
  77. bool is_passive_ = false;
  78. // model and data to be visualized
  79. mjModel* mnew_ = nullptr;
  80. mjData* dnew_ = nullptr;
  81. mjModel* m_ = nullptr;
  82. mjData* d_ = nullptr;
  83. int ncam_ = 0;
  84. int nkey_ = 0;
  85. int state_size_ = 0; // number of mjtNums in a history buffer state
  86. int nhistory_ = 0; // number of states saved in history buffer
  87. int history_cursor_ = 0; // cursor pointing at last saved state
  88. std::vector<int> body_parentid_;
  89. std::vector<int> jnt_type_;
  90. std::vector<int> jnt_group_;
  91. std::vector<int> jnt_qposadr_;
  92. std::vector<std::optional<std::pair<mjtNum, mjtNum>>> jnt_range_;
  93. std::vector<std::string> jnt_names_;
  94. std::vector<int> actuator_group_;
  95. std::vector<std::optional<std::pair<mjtNum, mjtNum>>> actuator_ctrlrange_;
  96. std::vector<std::string> actuator_names_;
  97. std::vector<mjtNum> history_; // history buffer (nhistory x state_size)
  98. // mjModel and mjData fields that can be modified by the user through the GUI
  99. std::vector<mjtNum> qpos_;
  100. std::vector<mjtNum> qpos_prev_;
  101. std::vector<mjtNum> ctrl_;
  102. std::vector<mjtNum> ctrl_prev_;
  103. mjvSceneState scnstate_;
  104. mjOption mjopt_prev_;
  105. mjvOption opt_prev_;
  106. mjvCamera cam_prev_;
  107. int warn_vgeomfull_prev_;
  108. // pending GUI-driven actions, to be applied at the next call to Sync
  109. struct {
  110. std::optional<std::string> save_xml;
  111. std::optional<std::string> save_mjb;
  112. std::optional<std::string> print_model;
  113. std::optional<std::string> print_data;
  114. bool reset;
  115. bool align;
  116. bool copy_pose;
  117. bool load_from_history;
  118. bool load_key;
  119. bool save_key;
  120. bool zero_ctrl;
  121. int newperturb;
  122. bool select;
  123. mjuiState select_state;
  124. bool ui_update_simulation;
  125. bool ui_update_physics;
  126. bool ui_update_rendering;
  127. bool ui_update_joint;
  128. bool ui_update_ctrl;
  129. bool ui_remake_ctrl;
  130. } pending_ = {};
  131. SimulateMutex mtx;
  132. std::condition_variable_any cond_loadrequest;
  133. int frames_ = 0;
  134. std::chrono::time_point<Clock> last_fps_update_;
  135. double fps_ = 0;
  136. // options
  137. int spacing = 0;
  138. int color = 0;
  139. int font = 0;
  140. int ui0_enable = 1;
  141. int ui1_enable = 1;
  142. int help = 0;
  143. int info = 0;
  144. int profiler = 0;
  145. int sensor = 0;
  146. int pause_update = 1;
  147. int fullscreen = 0;
  148. int vsync = 1;
  149. int busywait = 0;
  150. // keyframe index
  151. int key = 0;
  152. // index of history-scrubber slider
  153. int scrub_index = 0;
  154. // simulation
  155. int run = 1;
  156. // atomics for cross-thread messages
  157. std::atomic_int exitrequest = 0;
  158. std::atomic_int droploadrequest = 0;
  159. std::atomic_int screenshotrequest = 0;
  160. std::atomic_int uiloadrequest = 0;
  161. // loadrequest
  162. // 3: display a loading message
  163. // 2: render thread asked to update its model
  164. // 1: showing "loading" label, about to load
  165. // 0: model loaded or no load requested.
  166. int loadrequest = 0;
  167. // strings
  168. char load_error[kMaxFilenameLength] = "";
  169. char dropfilename[kMaxFilenameLength] = "";
  170. char filename[kMaxFilenameLength] = "";
  171. char previous_filename[kMaxFilenameLength] = "";
  172. // time synchronization
  173. int real_time_index = 0;
  174. bool speed_changed = true;
  175. float measured_slowdown = 1.0;
  176. // logarithmically spaced real-time slow-down coefficients (percent)
  177. static constexpr float percentRealTime[] = {
  178. 100, 80, 66, 50, 40, 33, 25, 20, 16, 13,
  179. 10, 8, 6.6, 5.0, 4, 3.3, 2.5, 2, 1.6, 1.3,
  180. 1, .8, .66, .5, .4, .33, .25, .2, .16, .13,
  181. .1
  182. };
  183. // control noise
  184. double ctrl_noise_std = 0.0;
  185. double ctrl_noise_rate = 0.0;
  186. // watch
  187. char field[mjMAXUITEXT] = "qpos";
  188. int index = 0;
  189. // physics: need sync
  190. int disable[mjNDISABLE] = {0};
  191. int enable[mjNENABLE] = {0};
  192. int enableactuator[mjNGROUP] = {0};
  193. // rendering: need sync
  194. int camera = 0;
  195. // abstract visualization
  196. mjvScene scn;
  197. mjvCamera& cam;
  198. mjvOption& opt;
  199. mjvPerturb& pert;
  200. mjvFigure figconstraint = {};
  201. mjvFigure figcost = {};
  202. mjvFigure figtimer = {};
  203. mjvFigure figsize = {};
  204. mjvFigure figsensor = {};
  205. // additional user-defined visualization geoms (used in passive mode)
  206. mjvScene* user_scn = nullptr;
  207. mjtByte user_scn_flags_prev_[mjNRNDFLAG];
  208. // OpenGL rendering and UI
  209. int refresh_rate = 60;
  210. int window_pos[2] = {0};
  211. int window_size[2] = {0};
  212. std::unique_ptr<PlatformUIAdapter> platform_ui;
  213. mjuiState& uistate;
  214. mjUI ui0 = {};
  215. mjUI ui1 = {};
  216. // Constant arrays needed for the option section of UI and the UI interface
  217. // TODO setting the size here is not ideal
  218. const mjuiDef def_option[13] = {
  219. {mjITEM_SECTION, "Option", mjPRESERVE, nullptr, "AO"},
  220. {mjITEM_CHECKINT, "Help", 2, &this->help, " #290"},
  221. {mjITEM_CHECKINT, "Info", 2, &this->info, " #291"},
  222. {mjITEM_CHECKINT, "Profiler", 2, &this->profiler, " #292"},
  223. {mjITEM_CHECKINT, "Sensor", 2, &this->sensor, " #293"},
  224. {mjITEM_CHECKINT, "Pause update", 2, &this->pause_update, ""},
  225. #ifdef __APPLE__
  226. {mjITEM_CHECKINT, "Fullscreen", 0, &this->fullscreen, " #294"},
  227. #else
  228. {mjITEM_CHECKINT, "Fullscreen", 1, &this->fullscreen, " #294"},
  229. #endif
  230. {mjITEM_CHECKINT, "Vertical Sync", 1, &this->vsync, ""},
  231. {mjITEM_CHECKINT, "Busy Wait", 1, &this->busywait, ""},
  232. {mjITEM_SELECT, "Spacing", 1, &this->spacing, "Tight\nWide"},
  233. {mjITEM_SELECT, "Color", 1, &this->color, "Default\nOrange\nWhite\nBlack"},
  234. {mjITEM_SELECT, "Font", 1, &this->font, "50 %\n100 %\n150 %\n200 %\n250 %\n300 %"},
  235. {mjITEM_END}
  236. };
  237. // simulation section of UI
  238. const mjuiDef def_simulation[14] = {
  239. {mjITEM_SECTION, "Simulation", mjPRESERVE, nullptr, "AS"},
  240. {mjITEM_RADIO, "", 5, &this->run, "Pause\nRun"},
  241. {mjITEM_BUTTON, "Reset", 2, nullptr, " #259"},
  242. {mjITEM_BUTTON, "Reload", 5, nullptr, "CL"},
  243. {mjITEM_BUTTON, "Align", 2, nullptr, "CA"},
  244. {mjITEM_BUTTON, "Copy pose", 2, nullptr, "CC"},
  245. {mjITEM_SLIDERINT, "Key", 3, &this->key, "0 0"},
  246. {mjITEM_BUTTON, "Load key", 3},
  247. {mjITEM_BUTTON, "Save key", 3},
  248. {mjITEM_SLIDERNUM, "Noise scale", 5, &this->ctrl_noise_std, "0 1"},
  249. {mjITEM_SLIDERNUM, "Noise rate", 5, &this->ctrl_noise_rate, "0 4"},
  250. {mjITEM_SEPARATOR, "History", 1},
  251. {mjITEM_SLIDERINT, "", 5, &this->scrub_index, "0 0"},
  252. {mjITEM_END}
  253. };
  254. // watch section of UI
  255. const mjuiDef def_watch[5] = {
  256. {mjITEM_SECTION, "Watch", mjPRESERVE, nullptr, "AW"},
  257. {mjITEM_EDITTXT, "Field", 2, this->field, "qpos"},
  258. {mjITEM_EDITINT, "Index", 2, &this->index, "1"},
  259. {mjITEM_STATIC, "Value", 2, nullptr, " "},
  260. {mjITEM_END}
  261. };
  262. // info strings
  263. char info_title[Simulate::kMaxFilenameLength] = {0};
  264. char info_content[Simulate::kMaxFilenameLength] = {0};
  265. // pending uploads
  266. std::condition_variable_any cond_upload_;
  267. int texture_upload_ = -1;
  268. int mesh_upload_ = -1;
  269. int hfield_upload_ = -1;
  270. };
  271. } // namespace mujoco
  272. #endif