mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
mj_kdl_wrapper.hpp File Reference
#include <mujoco/mujoco.h>
#include <GLFW/glfw3.h>
#include <kdl/chain.hpp>
#include <kdl/jntarray.hpp>
#include <functional>
#include <string>
#include <vector>
#include <chrono>
#include <thread>
#include <cstdio>
#include <cstring>
#include <sstream>

Go to the source code of this file.

Classes

struct  mj_kdl::AttachmentSpec
 
struct  mj_kdl::RobotSpec
 
struct  mj_kdl::TableSpec
 
struct  mj_kdl::SceneObject
 
struct  mj_kdl::SceneSpec
 
struct  mj_kdl::Robot
 
struct  mj_kdl::Viewer
 
struct  mj_kdl::VideoRecorder
 

Namespaces

namespace  mj_kdl
 

Macros

#define MJ_FILENAME_   (::strrchr(__FILE__, '/') ? ::strrchr(__FILE__, '/') + 1 : __FILE__)
 
#define MJ_LOG_(lvl_enum, color, label, expr)
 
#define LOG_INFO(expr)   MJ_LOG_(INFO, "", "INFO ", expr)
 
#define LOG_WARN(expr)   MJ_LOG_(WARN, "\033[33m", "WARN ", expr)
 
#define LOG_ERROR(expr)   MJ_LOG_(ERROR, "\033[31m", "ERROR", expr)
 

Typedefs

using mj_kdl::ControlCb = std::function< void(mjModel *m, mjData *d)>
 

Enumerations

enum class  mj_kdl::LogLevel { mj_kdl::LogLevel::NONE = 0 , mj_kdl::LogLevel::INFO = 1 , mj_kdl::LogLevel::WARN = 2 , mj_kdl::LogLevel::ERROR = 3 }
 
enum class  mj_kdl::Shape { mj_kdl::Shape::BOX , mj_kdl::Shape::SPHERE , mj_kdl::Shape::CYLINDER }
 
enum class  mj_kdl::CtrlMode { mj_kdl::CtrlMode::POSITION , mj_kdl::CtrlMode::TORQUE }
 
enum class  mj_kdl::VideoResolution {
  mj_kdl::VideoResolution::R360p = 360 , mj_kdl::VideoResolution::R480p = 480 , mj_kdl::VideoResolution::R720p = 720 , mj_kdl::VideoResolution::R1080p = 1080 ,
  mj_kdl::VideoResolution::R2K = 1440 , mj_kdl::VideoResolution::R4K = 2160
}
 

Functions

void mj_kdl::set_log_level (LogLevel level)
 
LogLevel mj_kdl::get_log_level ()
 
bool mj_kdl::save_model_xml (const mjModel *model, const char *path)
 
bool mj_kdl::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)
 
bool mj_kdl::attach_to_spec (mjSpec *robot_spec, const AttachmentSpec *a)
 
bool mj_kdl::build_scene (mjModel **out_model, mjData **out_data, const SceneSpec *spec)
 
void mj_kdl::destroy_scene (mjModel *model, mjData *data)
 
bool mj_kdl::init_window (Viewer *v, Robot *r, const char *title="MuJoCo", int width=1280, int height=720)
 
bool mj_kdl::init_window_sim (Viewer *v, Robot *r, const char *title="MuJoCo")
 
void mj_kdl::cleanup (Robot *r)
 
void mj_kdl::cleanup (Viewer *v)
 
bool mj_kdl::init_video_recorder (VideoRecorder *vr, mjModel *model, const char *out_path, int width=1280, int height=720, int fps=60)
 
bool mj_kdl::init_video_recorder (VideoRecorder *vr, mjModel *model, const char *out_path, VideoResolution resolution, int fps=60)
 
bool mj_kdl::record_frame (VideoRecorder *vr, mjModel *model, mjData *data)
 
void mj_kdl::cleanup (VideoRecorder *vr)
 
void mj_kdl::step (Robot *s)
 
void mj_kdl::step_n (Robot *s, int n)
 
void mj_kdl::reset (Robot *s)
 
bool mj_kdl::is_running (const Viewer *v)
 
bool mj_kdl::render (Viewer *v, const Robot *r)
 
bool mj_kdl::render (Viewer *v, mjModel *m, mjData *d)
 
bool mj_kdl::tick (Viewer *v, Robot *r)
 
bool mj_kdl::tick (Viewer *v, mjModel *m, mjData *d)
 
void mj_kdl::update (Robot *r)
 
void mj_kdl::set_joint_pos (Robot *r, const KDL::JntArray &q, bool call_forward=true)
 
bool mj_kdl::scene_add_object (mjModel **model, mjData **data, SceneSpec *spec, const SceneObject &obj)
 
bool mj_kdl::scene_remove_object (mjModel **model, mjData **data, SceneSpec *spec, const std::string &name)
 
void mj_kdl::run_simulate_ui (mjModel *m, mjData *d, const char *path, ControlCb physics_cb=nullptr)
 
void mj_kdl::add_skybox_to_spec (mjSpec *spec)
 
void mj_kdl::add_floor_to_spec (mjSpec *spec)
 
void mj_kdl::add_table_to_spec (mjSpec *spec, const TableSpec &t)
 
void mj_kdl::add_objects_to_spec (mjSpec *spec, const std::vector< SceneObject > &objects)
 
void mj_kdl::configure_spec (mjSpec *spec, const SceneSpec *sc)
 
bool mj_kdl::compile_and_make_data (mjSpec *spec, mjModel **out_model, mjData **out_data)
 
void mj_kdl::ensure_plugins_loaded ()
 

Variables

LogLevel mj_kdl::g_log_level = LogLevel::ERROR
 

Macro Definition Documentation

◆ LOG_ERROR

#define LOG_ERROR (   expr)    MJ_LOG_(ERROR, "\033[31m", "ERROR", expr)

Definition at line 64 of file mj_kdl_wrapper.hpp.

◆ LOG_INFO

#define LOG_INFO (   expr)    MJ_LOG_(INFO, "", "INFO ", expr)

Definition at line 62 of file mj_kdl_wrapper.hpp.

◆ LOG_WARN

#define LOG_WARN (   expr)    MJ_LOG_(WARN, "\033[33m", "WARN ", expr)

Definition at line 63 of file mj_kdl_wrapper.hpp.

◆ MJ_FILENAME_

#define MJ_FILENAME_   (::strrchr(__FILE__, '/') ? ::strrchr(__FILE__, '/') + 1 : __FILE__)

Definition at line 44 of file mj_kdl_wrapper.hpp.

◆ MJ_LOG_

#define MJ_LOG_ (   lvl_enum,
  color,
  label,
  expr 
)
Value:
do { \
if (::mj_kdl::g_log_level >= ::mj_kdl::LogLevel::lvl_enum) { \
std::ostringstream _mj_oss; \
_mj_oss << expr; \
std::fprintf( \
stderr, \
color "[mj_kdl " label "] %s:%d (%s): %s\033[0m\n", \
__LINE__, \
__func__, \
_mj_oss.str().c_str() \
); \
} \
} while (0)
LogLevel g_log_level
#define MJ_FILENAME_

Definition at line 46 of file mj_kdl_wrapper.hpp.