Skip to content

Commit

Permalink
refactor: reduces viewer excess padding
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidPL1 committed Nov 8, 2024
1 parent 1eda184 commit 995b5db
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 33 deletions.
58 changes: 27 additions & 31 deletions mujoco_ros/include/mujoco_ros/viewer.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,13 +135,16 @@ class Viewer
static constexpr double render_ui_rate_lower_bound_ = 0.0333; // Minimum render freq at 30 fps
static constexpr float render_ui_rate_upper_bound_ = 0.0166f; // Maximum render freq at 60 fps

// whether the viewer is operating in passive mode, where it cannot assume
// that it has exclusive access to the model, data, and various mjv objects
bool is_passive_ = false;

// Reference to env
MujocoEnv *env_;

std::chrono::time_point<Clock> last_fps_update_;
double fps_ = 0;

// control noise
double ctrl_noise_std = 0.0;
double ctrl_noise_rate = 0.0;

// model and data to be visualized
mjModelPtr mnew_;
mjDataPtr dnew_;
Expand All @@ -150,10 +153,13 @@ class Viewer
mjDataPtr d_;

int ncam_ = 0;
int camera = 0;
int nkey_ = 0;
int index = 0;
int state_size_ = 0; // number of mjtNums in a history buffer state
int nhistory_ = 0; // number of states saved in history buffer
int history_cursor_ = 0; // cursor pointing at last saved state
int scrub_index = 0; // index of history-scrubber slider

std::vector<int> body_parentid_;

Expand All @@ -178,13 +184,13 @@ class Viewer
mjvSceneState scnstate_;
mjOption mjopt_prev_;
mjvOption opt_prev_;
mjvCamera cam_prev_;

int warn_vgeomfull_prev_;
mjvCamera cam_prev_;

// pending GUI-driven actions, to be applied at the next call to Sync
struct
{
mjuiState select_state;
std::optional<std::string> save_xml;
std::optional<std::string> save_mjb;
std::optional<std::string> print_model;
Expand All @@ -193,11 +199,10 @@ class Viewer
bool copy_pose;
bool load_from_history;
bool load_key;
int newperturb;
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;
Expand All @@ -211,14 +216,13 @@ class Viewer
bool ui_update_speed = false;
bool ui_reset = false;
bool ui_reload = false;

} pending_ = {};

ViewerMutex mtx; // Should move to MujocoEnv
std::condition_variable_any cond_loadrequest;

int frames_ = 0;
std::chrono::time_point<Clock> last_fps_update_;
double fps_ = 0;

// options
int spacing = 0;
Expand All @@ -238,12 +242,6 @@ class Viewer
// keyframe index
int key = 0;

// index of history-scrubber slider
int scrub_index = 0;

// UI proxy elements for Env settings
int run = 0;

// atomics for cross-thread messages
std::atomic_int exit_request = { 0 };
std::atomic_int visual_init_request = { 0 };
Expand Down Expand Up @@ -271,39 +269,36 @@ class Viewer
int real_time_index = 1;
float measured_slowdown = 1.0f;

// control noise
double ctrl_noise_std = 0.0;
double ctrl_noise_rate = 0.0;

// watch
char field[mjMAXUITEXT] = "qpos";
int index = 0;

// physics: need sync
int disable[mjNDISABLE] = { 0 };
int enable[mjNENABLE] = { 0 };
int enableactuator[mjNGROUP] = { 0 };

// rendering: need sync
int camera = 0;

// visualization
mjvScene scn;
mjvCamera cam;
mjvOption opt;
int refresh_rate = 60;
mjvPerturb &pert;
mjvFigure figconstraint = {};
mjvFigure figcost = {};
mjvFigure figtimer = {};
mjvFigure figsize = {};
mjvFigure figsensor = {};

// pending uploads
int texture_upload_ = -1;
int mesh_upload_ = -1;
int hfield_upload_ = -1;
std::condition_variable_any cond_upload_;

// additional user-defined viszualization geoms
mjvScene *user_scn = nullptr;
mjtByte user_scn_flags_prev_[mjNRNDFLAG];

// OpenGL rendering and UI
int refresh_rate = 60;
int window_pos[2] = { 0 };
int window_size[2] = { 0 };
std::unique_ptr<PlatformUIAdapter> platform_ui;
Expand Down Expand Up @@ -355,11 +350,12 @@ class Viewer
char info_title[Viewer::kMaxFilenameLength] = { 0 };
char info_content[Viewer::kMaxFilenameLength] = { 0 };

// pending uploads
std::condition_variable_any cond_upload_;
int texture_upload_ = -1;
int mesh_upload_ = -1;
int hfield_upload_ = -1;
mjtByte user_scn_flags_prev_[mjNRNDFLAG];
// whether the viewer is operating in passive mode, where it cannot assume
// that it has exclusive access to the model, data, and various mjv objects
bool is_passive_ = false;

int run = 0;
};

} // namespace mujoco_ros
4 changes: 2 additions & 2 deletions mujoco_ros/src/viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1755,11 +1755,11 @@ namespace mujoco_ros {
namespace mju = ::mujoco::sample_util;

Viewer::Viewer(std::unique_ptr<PlatformUIAdapter> platform_ui_adapter, MujocoEnv *env, bool is_passive)
: is_passive_(is_passive)
, env_(env)
: env_(env)
, pert(env->pert_)
, platform_ui(std::move(platform_ui_adapter))
, uistate(this->platform_ui->state())
, is_passive_(is_passive)
{
mjv_defaultScene(&scn);
mjv_defaultSceneState(&scnstate_);
Expand Down

0 comments on commit 995b5db

Please sign in to comment.