| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SIMULATE_SIMULATE_H_ |
| | #define MUJOCO_SIMULATE_SIMULATE_H_ |
| |
|
| | #include <atomic> |
| | #include <chrono> |
| | #include <condition_variable> |
| | #include <memory> |
| | #include <mutex> |
| | #include <optional> |
| | #include <ratio> |
| | #include <string> |
| | #include <tuple> |
| | #include <utility> |
| | #include <vector> |
| |
|
| | #include <mujoco/mjui.h> |
| | #include <mujoco/mujoco.h> |
| | #include "platform_ui_adapter.h" |
| |
|
| | namespace mujoco { |
| |
|
| | |
| | |
| | |
| | |
| | |
| | class SimulateMutex : public std::recursive_mutex {}; |
| | using MutexLock = std::unique_lock<std::recursive_mutex>; |
| |
|
| | |
| | class Simulate { |
| | public: |
| | using Clock = std::chrono::steady_clock; |
| | static_assert(std::ratio_less_equal_v<Clock::period, std::milli>); |
| |
|
| | static constexpr int kMaxGeom = 20000; |
| |
|
| | |
| | Simulate( |
| | std::unique_ptr<PlatformUIAdapter> platform_ui_adapter, |
| | mjvCamera* cam, mjvOption* opt, mjvPerturb* pert, bool is_passive); |
| |
|
| | |
| | |
| | |
| | void Sync(bool state_only = false); |
| |
|
| | void UpdateHField(int hfieldid); |
| | void UpdateMesh(int meshid); |
| | void UpdateTexture(int texid); |
| |
|
| | |
| | |
| | void LoadMessage(const char* displayed_filename); |
| |
|
| | |
| | void Load(mjModel* m, mjData* d, const char* displayed_filename); |
| |
|
| | |
| | |
| | |
| | void LoadMessageClear(void); |
| |
|
| | |
| | |
| | void LoadOnRenderThread(); |
| |
|
| | |
| | void Render(); |
| |
|
| | |
| | void RenderLoop(); |
| |
|
| | |
| | void AddToHistory(); |
| |
|
| | |
| | void InjectNoise(); |
| |
|
| | |
| | static constexpr int kMaxFilenameLength = 1000; |
| |
|
| | |
| | |
| | bool is_passive_ = false; |
| |
|
| | |
| | mjModel* mnew_ = nullptr; |
| | mjData* dnew_ = nullptr; |
| |
|
| | mjModel* m_ = nullptr; |
| | mjData* d_ = nullptr; |
| |
|
| | int ncam_ = 0; |
| | int nkey_ = 0; |
| | int state_size_ = 0; |
| | int nhistory_ = 0; |
| | int history_cursor_ = 0; |
| |
|
| | std::vector<int> body_parentid_; |
| |
|
| | std::vector<int> jnt_type_; |
| | std::vector<int> jnt_group_; |
| | std::vector<int> jnt_qposadr_; |
| | std::vector<std::optional<std::pair<mjtNum, mjtNum>>> jnt_range_; |
| | std::vector<std::string> jnt_names_; |
| |
|
| | std::vector<int> actuator_group_; |
| | std::vector<std::optional<std::pair<mjtNum, mjtNum>>> actuator_ctrlrange_; |
| | std::vector<std::string> actuator_names_; |
| |
|
| | std::vector<std::string> equality_names_; |
| |
|
| | std::vector<mjtNum> history_; |
| |
|
| | |
| | std::vector<mjtNum> qpos_; |
| | std::vector<mjtNum> qpos_prev_; |
| | std::vector<mjtNum> ctrl_; |
| | std::vector<mjtNum> ctrl_prev_; |
| | std::vector<mjtByte> eq_active_; |
| | std::vector<mjtByte> eq_active_prev_; |
| |
|
| | |
| | |
| | mjModel* m_passive_ = nullptr; |
| | mjData* d_passive_ = nullptr; |
| | std::vector<mjvGeom> user_scn_geoms_; |
| |
|
| | mjOption mjopt_prev_; |
| | mjVisual mjvis_prev_; |
| | mjStatistic mjstat_prev_; |
| | mjvOption opt_prev_; |
| | mjvCamera cam_prev_; |
| |
|
| | int warn_vgeomfull_prev_; |
| |
|
| | |
| | struct { |
| | std::optional<std::string> save_xml; |
| | std::optional<std::string> save_mjb; |
| | std::optional<std::string> print_model; |
| | std::optional<std::string> print_data; |
| | bool reset; |
| | bool align; |
| | bool copy_key; |
| | bool copy_key_full_precision; |
| | bool load_from_history; |
| | bool load_key; |
| | bool save_key; |
| | bool zero_ctrl; |
| | int newperturb; |
| | bool select; |
| | mjuiState select_state; |
| | bool ui_update_simulation; |
| | bool ui_update_physics; |
| | bool ui_update_rendering; |
| | bool ui_update_visualization; |
| | bool ui_update_joint; |
| | bool ui_update_ctrl; |
| | bool ui_update_equality; |
| | bool ui_remake_ctrl; |
| | } pending_ = {}; |
| |
|
| | SimulateMutex mtx; |
| | std::condition_variable_any cond_loadrequest; |
| |
|
| | int frames_ = 0; |
| | std::chrono::time_point<Clock> last_fps_update_; |
| | double fps_ = 0; |
| |
|
| | |
| | int spacing = 0; |
| | int color = 0; |
| | int font = 0; |
| | int ui0_enable = 1; |
| | int ui1_enable = 1; |
| | int help = 0; |
| | int info = 0; |
| | int profiler = 0; |
| | int sensor = 0; |
| | int pause_update = 1; |
| | int fullscreen = 0; |
| | int vsync = 1; |
| | int busywait = 0; |
| |
|
| | |
| | int key = 0; |
| |
|
| | |
| | int scrub_index = 0; |
| |
|
| | |
| | int run = 1; |
| |
|
| | |
| | std::atomic_int exitrequest = 0; |
| | std::atomic_int droploadrequest = 0; |
| | std::atomic_int screenshotrequest = 0; |
| | std::atomic_int uiloadrequest = 0; |
| | std::atomic_int newfigurerequest = 0; |
| | std::atomic_int newtextrequest = 0; |
| | std::atomic_int newimagerequest = 0; |
| |
|
| | |
| | |
| | |
| | |
| | |
| | int loadrequest = 0; |
| |
|
| | |
| | char load_error[kMaxFilenameLength] = ""; |
| | char dropfilename[kMaxFilenameLength] = ""; |
| | char filename[kMaxFilenameLength] = ""; |
| | char previous_filename[kMaxFilenameLength] = ""; |
| |
|
| | |
| | int real_time_index = 0; |
| | bool speed_changed = true; |
| | float measured_slowdown = 1.0; |
| | |
| | static constexpr float percentRealTime[] = { |
| | 100, 80, 66, 50, 40, 33, 25, 20, 16, 13, |
| | 10, 8, 6.6, 5.0, 4, 3.3, 2.5, 2, 1.6, 1.3, |
| | 1, .8, .66, .5, .4, .33, .25, .2, .16, .13, |
| | .1 |
| | }; |
| |
|
| | |
| | double ctrl_noise_std = 0.0; |
| | double ctrl_noise_rate = 0.0; |
| |
|
| | |
| | char field[mjMAXUITEXT] = "qpos"; |
| | int index = 0; |
| |
|
| | |
| | int disable[mjNDISABLE] = {0}; |
| | int enable[mjNENABLE] = {0}; |
| | int enableactuator[mjNGROUP] = {0}; |
| |
|
| | |
| | int camera = 0; |
| |
|
| | |
| | mjvScene scn; |
| | mjvCamera& cam; |
| | mjvOption& opt; |
| | mjvPerturb& pert; |
| | mjvFigure figconstraint = {}; |
| | mjvFigure figcost = {}; |
| | mjvFigure figtimer = {}; |
| | mjvFigure figsize = {}; |
| | mjvFigure figsensor = {}; |
| |
|
| | |
| | mjvScene* user_scn = nullptr; |
| | mjtByte user_scn_flags_prev_[mjNRNDFLAG]; |
| | std::vector<std::pair<mjrRect, mjvFigure>> user_figures_; |
| | std::vector<std::pair<mjrRect, mjvFigure>> user_figures_new_; |
| | std::vector<std::tuple<int, int, std::string, std::string>> user_texts_; |
| | std::vector<std::tuple<int, int, std::string, std::string>> user_texts_new_; |
| | std::vector<std::tuple<mjrRect, std::unique_ptr<unsigned char[]>>> user_images_; |
| | std::vector<std::tuple<mjrRect, std::unique_ptr<unsigned char[]>>> user_images_new_; |
| |
|
| | |
| | int refresh_rate = 60; |
| | int window_pos[2] = {0}; |
| | int window_size[2] = {0}; |
| | std::unique_ptr<PlatformUIAdapter> platform_ui; |
| | mjuiState& uistate; |
| | mjUI ui0 = {}; |
| | mjUI ui1 = {}; |
| |
|
| | |
| | |
| | const mjuiDef def_option[13] = { |
| | {mjITEM_SECTION, "Option", mjPRESERVE, nullptr, "AO"}, |
| | {mjITEM_CHECKINT, "Help", 2, &this->help, " #290"}, |
| | {mjITEM_CHECKINT, "Info", 2, &this->info, " #291"}, |
| | {mjITEM_CHECKINT, "Profiler", 2, &this->profiler, " #292"}, |
| | {mjITEM_CHECKINT, "Sensor", 2, &this->sensor, " #293"}, |
| | {mjITEM_CHECKINT, "Pause update", 2, &this->pause_update, ""}, |
| | #ifdef __APPLE__ |
| | {mjITEM_CHECKINT, "Fullscreen", 0, &this->fullscreen, " #294"}, |
| | #else |
| | {mjITEM_CHECKINT, "Fullscreen", 1, &this->fullscreen, " #294"}, |
| | #endif |
| | {mjITEM_CHECKINT, "Vertical Sync", 1, &this->vsync, ""}, |
| | {mjITEM_CHECKINT, "Busy Wait", 1, &this->busywait, ""}, |
| | {mjITEM_SELECT, "Spacing", 1, &this->spacing, "Tight\nWide"}, |
| | {mjITEM_SELECT, "Color", 1, &this->color, "Default\nOrange\nWhite\nBlack"}, |
| | {mjITEM_SELECT, "Font", 1, &this->font, "50 %\n100 %\n150 %\n200 %\n250 %\n300 %"}, |
| | {mjITEM_END} |
| | }; |
| |
|
| |
|
| | |
| | const mjuiDef def_simulation[14] = { |
| | {mjITEM_SECTION, "Simulation", mjPRESERVE, nullptr, "AS"}, |
| | {mjITEM_RADIO, "", 5, &this->run, "Pause\nRun"}, |
| | {mjITEM_BUTTON, "Reset", 2, nullptr, " #259"}, |
| | {mjITEM_BUTTON, "Reload", 5, nullptr, "CL"}, |
| | {mjITEM_BUTTON, "Align", 2, nullptr, "CA"}, |
| | {mjITEM_BUTTON, "Copy state", 2, nullptr, "CC"}, |
| | {mjITEM_SLIDERINT, "Key", 3, &this->key, "0 0"}, |
| | {mjITEM_BUTTON, "Load key", 3}, |
| | {mjITEM_BUTTON, "Save key", 3}, |
| | {mjITEM_SLIDERNUM, "Noise scale", 5, &this->ctrl_noise_std, "0 1"}, |
| | {mjITEM_SLIDERNUM, "Noise rate", 5, &this->ctrl_noise_rate, "0 4"}, |
| | {mjITEM_SEPARATOR, "History", 1}, |
| | {mjITEM_SLIDERINT, "", 5, &this->scrub_index, "0 0"}, |
| | {mjITEM_END} |
| | }; |
| |
|
| |
|
| | |
| | const mjuiDef def_watch[5] = { |
| | {mjITEM_SECTION, "Watch", mjPRESERVE, nullptr, "AW"}, |
| | {mjITEM_EDITTXT, "Field", 2, this->field, "qpos"}, |
| | {mjITEM_EDITINT, "Index", 2, &this->index, "1"}, |
| | {mjITEM_STATIC, "Value", 2, nullptr, " "}, |
| | {mjITEM_END} |
| | }; |
| |
|
| | |
| | char info_title[Simulate::kMaxFilenameLength] = {0}; |
| | char info_content[Simulate::kMaxFilenameLength] = {0}; |
| |
|
| | |
| | std::condition_variable_any cond_upload_; |
| | int texture_upload_ = -1; |
| | int mesh_upload_ = -1; |
| | int hfield_upload_ = -1; |
| | }; |
| | } |
| |
|
| | #endif |
| |
|