Viewer¶
MuJoCoViewer¶
-
class
MuJoCoViewer¶ Helper class to render a MuJoCo model
Callback methods
Methods are called from inside the window.
-
void
cb_keyboard(GLFWwindow *window, int key, int scancode, int act, int mods)¶
-
void
cb_mouse_move(GLFWwindow *window, double xpos, double ypos)¶
-
void
cb_scroll(GLFWwindow *window, double xoffset, double yoffset)¶
Public Functions
-
MuJoCoViewer(const mjModel *m = nullptr)¶ Constructor
- Parameters
m: Model to be linked to
-
MuJoCoViewer(const MuJoCoModel &model)¶ Constructor Model to be linked to
- Parameters
model:
-
~MuJoCoViewer()¶
-
bool
window_should_close() const¶ Return true when window was closed
-
void
update(mjData *d = nullptr)¶ Render new scene and poll for glwfw events
Leave d empty to not update the scene.
- Parameters
d: New data
-
void
play(mjData *d)¶ Run simulation until window is closed
Function steps through simulation and displays it, running in real-time.
-
void
update_scene(mjData *d)¶ Update scene with mjData
-
void
initialize(const mjModel *m)¶ Initialize viewer with model
Typically only called from inside the constructor.
-
void
draw_arrow(const double vector[3], const double base[3])¶ Create arrow from the given vector, starting from the base
Arrow will only show up if added after scene update!
- Parameters
vector: Vector itselfbase: Location of the base
-
void
add_figure(MuJoCoFigure *figure)¶ Add new figure
When the figure does not have an explicit position, it will be place above the previous figure.
- Parameters
figure: Pointer to existing figure
Public Members
Mouse buttons
-
double
mouse_x_¶ Last known mouse position
-
double
mouse_y_¶
-
const mjModel *
m_¶ Pointer to MJ model object
-
mjvCamera
cam_¶ MJ camera object
-
mjvOption
opt_¶ MJ visualisations options
-
mjvScene
scn_¶ MJ scene
-
mjrContext
con_¶ MJ GPU context
Public Static Functions
-
MuJoCoViewer *
get_viewer_ptr(GLFWwindow *window)¶ Get original object reference which was tucked inside the window
-
void
sleep_seconds(double seconds)¶ Let current thread wait for an amount of seconds
- Parameters
seconds: Time in seconds
-
void
MuJoCoFigure¶
-
class
MuJoCoFigure¶ Figure (graph) to be shown inside MuJoCoViewer
One figure corresponds to one graph. One figure can consist of multiple lines (curves).
Figure object needs to be linked once to MuJoCoViewer using MuJoCoViewer.add_figure().
Set legends
-
MuJoCoFigure &
set_legends(const std::vector<std::string> &legends)¶ - Parameters
legends: Set list of legends
-
MuJoCoFigure &
set_legend(const std::string &legend)¶ - Parameters
legend: Set a single legend
Set new values in figure
- Parameters
x: Current time (x-axis value)
-
void
add_value(double x, double val, int line_id = 0)¶ Set a single value.
- Parameters
x:val: New valueline_id: Index of line (< n_lines)
-
void
add_values(double x, const double *values, int n_values = -1)¶ Set values for multiple lines.
- Parameters
x:values: Array of new valuesn_values: Size of array
Public Functions
-
MuJoCoFigure()¶ Default consstructor
-
MuJoCoFigure(const std::string &name, int n_lines = 1)¶ Constructor
- Parameters
name: Title of the figuren_lines: Number of lines in figure
-
~MuJoCoFigure() = default¶
-
mjrRect
get_viewport() const¶ Return viewport
-
MuJoCoFigure &
set_x_label(const std::string &label)¶ Set label for x-axis
-
MuJoCoFigure &
set_size(int width, int height)¶ Set figure width and height
-
MuJoCoFigure &
set_pos(int x, int y)¶ Set figure screen position
-
mjvFigure *
get_figure()¶ Return mjFigure pointer
-
void
get_pos(int &x_res, int &y_res)¶ Get screen position
-
void
get_size(int &width_res, int &height_res)¶ Get screen size
-
void
clear()¶ Clear figure entirely
-
MuJoCoFigure &