mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
mj_kdl::Robot Struct Reference

#include <mj_kdl_wrapper.hpp>

Public Attributes

mjModel * model = nullptr
 
mjData * data = nullptr
 
KDL::Chain chain
 
int n_joints = 0
 
std::vector< std::string > joint_names
 
std::vector< std::pair< double, double > > joint_limits
 
CtrlMode ctrl_mode = CtrlMode::POSITION
 
bool paused = false
 
std::vector< double > jnt_pos_msr
 
std::vector< double > jnt_vel_msr
 
std::vector< double > jnt_trq_msr
 
std::vector< double > jnt_pos_cmd
 
std::vector< double > jnt_trq_cmd
 
std::vector< int > kdl_to_mj_qpos
 
std::vector< int > kdl_to_mj_dof
 
std::vector< int > kdl_to_mj_ctrl
 

Detailed Description

Runtime handle for one KDL-tracked articulation inside a MuJoCo scene. model/data are borrowed (never freed by cleanup()); call destroy_scene() separately.

Workflow:

  1. Call init_robot_from_mjcf() - populates configuration and sizes port vectors to n_joints.
  2. Each control step: read *_msr ports (updated by update()), fill *_cmd ports, call update() to apply commands to MuJoCo and read back sensor state.

Definition at line 190 of file mj_kdl_wrapper.hpp.

Member Data Documentation

◆ chain

◆ ctrl_mode

CtrlMode mj_kdl::Robot::ctrl_mode = CtrlMode::POSITION

◆ data

mjData* mj_kdl::Robot::data = nullptr

Definition at line 194 of file mj_kdl_wrapper.hpp.

Referenced by MjcfLoadTest::SetUp().

◆ jnt_pos_cmd

std::vector<double> mj_kdl::Robot::jnt_pos_cmd

◆ jnt_pos_msr

std::vector<double> mj_kdl::Robot::jnt_pos_msr

Definition at line 203 of file mj_kdl_wrapper.hpp.

Referenced by main(), and MjcfPickTest::run_phase().

◆ jnt_trq_cmd

std::vector<double> mj_kdl::Robot::jnt_trq_cmd

Definition at line 207 of file mj_kdl_wrapper.hpp.

Referenced by main(), MjcfPickTest::reset_scene(), and MjcfPickTest::run_phase().

◆ jnt_trq_msr

std::vector<double> mj_kdl::Robot::jnt_trq_msr

Definition at line 205 of file mj_kdl_wrapper.hpp.

◆ jnt_vel_msr

std::vector<double> mj_kdl::Robot::jnt_vel_msr

Definition at line 204 of file mj_kdl_wrapper.hpp.

Referenced by main().

◆ joint_limits

std::vector<std::pair<double, double> > mj_kdl::Robot::joint_limits

Definition at line 198 of file mj_kdl_wrapper.hpp.

◆ joint_names

std::vector<std::string> mj_kdl::Robot::joint_names

Definition at line 197 of file mj_kdl_wrapper.hpp.

Referenced by main().

◆ kdl_to_mj_ctrl

std::vector<int> mj_kdl::Robot::kdl_to_mj_ctrl

Definition at line 212 of file mj_kdl_wrapper.hpp.

◆ kdl_to_mj_dof

std::vector<int> mj_kdl::Robot::kdl_to_mj_dof

◆ kdl_to_mj_qpos

std::vector<int> mj_kdl::Robot::kdl_to_mj_qpos

Definition at line 210 of file mj_kdl_wrapper.hpp.

Referenced by main(), MjcfPickTest::reset_scene(), and MjcfLoadTest::SetUp().

◆ model

mjModel* mj_kdl::Robot::model = nullptr

Definition at line 193 of file mj_kdl_wrapper.hpp.

◆ n_joints

int mj_kdl::Robot::n_joints = 0

◆ paused

bool mj_kdl::Robot::paused = false

Definition at line 202 of file mj_kdl_wrapper.hpp.


The documentation for this struct was generated from the following file: