7#include <mujoco/mujoco.h>
9#include <kdl/chain.hpp>
10#include <kdl/jntarray.hpp>
44#define MJ_FILENAME_ (::strrchr(__FILE__, '/') ? ::strrchr(__FILE__, '/') + 1 : __FILE__)
46#define MJ_LOG_(lvl_enum, color, label, expr) \
48 if (::mj_kdl::g_log_level >= ::mj_kdl::LogLevel::lvl_enum) { \
49 std::ostringstream _mj_oss; \
53 color "[mj_kdl " label "] %s:%d (%s): %s\033[0m\n", \
57 _mj_oss.str().c_str() \
62#define LOG_INFO(expr) MJ_LOG_(INFO, "", "INFO ", expr)
63#define LOG_WARN(expr) MJ_LOG_(WARN, "\033[33m", "WARN ", expr)
64#define LOG_ERROR(expr) MJ_LOG_(ERROR, "\033[31m", "ERROR", expr)
78 double pos[3] = { 0, 0, 0 };
104 double pos[3] = { 0, 0, 0 };
117 double pos[3] = { 0.0, 0.0, 0.7 };
121 float rgba[4] = { 0.45f, 0.28f, 0.12f, 1.0f };
150 double size[3] = { 0.03, 0.03, 0.03 };
151 double pos[3] = { 0.0, 0.0, 0.0 };
152 float rgba[4] = { 1.0f, 0.0f, 0.0f, 1.0f };
229 std::chrono::steady_clock::time_point
_tick_t{};
316 const char *base_body,
317 const char *tip_body,
318 const char *prefix =
"",
319 const char *tool_body =
nullptr
376 const char *title =
"MuJoCo",
433 const char *out_path,
454 const char *out_path,
621using ControlCb = std::function<void(mjModel *m, mjData *d)>;
634[[deprecated(
"prefer init_window_sim() + tick()")]]
void
void add_skybox_to_spec(mjSpec *spec)
void add_table_to_spec(mjSpec *spec, const TableSpec &t)
bool compile_and_make_data(mjSpec *spec, mjModel **out_model, mjData **out_data)
void add_objects_to_spec(mjSpec *spec, const std::vector< SceneObject > &objects)
void add_floor_to_spec(mjSpec *spec)
void ensure_plugins_loaded()
void configure_spec(mjSpec *spec, const SceneSpec *sc)
void set_log_level(LogLevel level)
bool init_video_recorder(VideoRecorder *vr, mjModel *model, const char *out_path, int width=1280, int height=720, int fps=60)
bool record_frame(VideoRecorder *vr, mjModel *model, mjData *data)
bool init_robot_from_mjcf(Robot *r, mjModel *model, mjData *data, const char *base_body, const char *tip_body, const char *prefix="", const char *tool_body=nullptr)
void step_n(Robot *s, int n)
void set_joint_pos(Robot *r, const KDL::JntArray &q, bool call_forward=true)
bool build_scene(mjModel **out_model, mjData **out_data, const SceneSpec *spec)
bool attach_to_spec(mjSpec *robot_spec, const AttachmentSpec *a)
bool scene_add_object(mjModel **model, mjData **data, SceneSpec *spec, const SceneObject &obj)
bool scene_remove_object(mjModel **model, mjData **data, SceneSpec *spec, const std::string &name)
void destroy_scene(mjModel *model, mjData *data)
bool save_model_xml(const mjModel *model, const char *path)
bool init_window_sim(Viewer *v, Robot *r, const char *title="MuJoCo")
bool tick(Viewer *v, Robot *r)
bool init_window(Viewer *v, Robot *r, const char *title="MuJoCo", int width=1280, int height=720)
bool render(Viewer *v, const Robot *r)
bool is_running(const Viewer *v)
void run_simulate_ui(mjModel *m, mjData *d, const char *path, ControlCb physics_cb=nullptr)
std::function< void(mjModel *m, mjData *d)> ControlCb
std::vector< std::pair< std::string, std::string > > contact_exclusions
std::vector< AttachmentSpec > attachments
std::vector< int > kdl_to_mj_ctrl
std::vector< int > kdl_to_mj_qpos
std::vector< int > kdl_to_mj_dof
std::vector< double > jnt_pos_msr
std::vector< double > jnt_pos_cmd
std::vector< std::pair< double, double > > joint_limits
std::vector< double > jnt_vel_msr
std::vector< double > jnt_trq_cmd
std::vector< double > jnt_trq_msr
std::vector< std::string > joint_names
std::vector< RobotSpec > robots
std::vector< SceneObject > objects
std::chrono::steady_clock::time_point _tick_t