mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
ex_gravity_comp.cpp
Go to the documentation of this file.
1/* ex_gravity_comp.cpp (MJCF)
2 * KDL gravity compensation on the Kinova GEN3 loaded from MuJoCo Menagerie MJCF.
3 *
4 * Each physics step computes joint gravity torques via
5 * KDL::ChainDynParam::JntToGravity and applies them via update() in
6 * TORQUE mode, keeping the arm floating at home pose.
7 *
8 * Requires third_party/menagerie submodule.
9 *
10 * Usage:
11 * ex_gravity_comp_mjcf [--headless]
12 *
13 * With --headless runs 500 steps and prints the final EE drift. */
14
16
17#include <kdl/chaindynparam.hpp>
18#include <kdl/chainfksolverpos_recursive.hpp>
19
20#include <filesystem>
21#include <iomanip>
22#include <iostream>
23#include <string>
24
25static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
26
27namespace fs = std::filesystem;
28static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path().parent_path(); }
29
30int main(int argc, char *argv[])
31{
32 bool headless = false;
33 for (int i = 1; i < argc; ++i)
34 if (std::string(argv[i]) == "--headless") headless = true;
35
36 const fs::path root = repo_root();
37 if (!fs::exists(root / "third_party/menagerie")) {
38 std::cerr << "third_party/menagerie/ not found - run:\n"
39 " cmake -B build -DFETCH_MENAGERIE=ON\n";
40 return 1;
41 }
42
43 const std::string mjcf = (root / "third_party/menagerie/kinova_gen3/gen3.xml").string();
44
47 r.path = mjcf.c_str();
48 sc.robots.push_back(r);
49
50 mjModel *model = nullptr;
51 mjData *data = nullptr;
52 mj_kdl::Robot robot;
53 if (!mj_kdl::build_scene(&model, &data, &sc)) {
54 std::cerr << "build_scene() failed\n";
55 return 1;
56 }
57 if (!mj_kdl::init_robot_from_mjcf(&robot, model, data, "base_link", "bracelet_link")) {
58 std::cerr << "init_robot_from_mjcf() failed\n";
59 mj_kdl::destroy_scene(model, data);
60 return 1;
61 }
62
63 unsigned n = static_cast<unsigned>(robot.n_joints);
64 KDL::ChainFkSolverPos_recursive fk(robot.chain);
65 KDL::ChainDynParam dyn(robot.chain, KDL::Vector(0.0, 0.0, -9.81));
66
67 KDL::JntArray q_home(n);
68 for (unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
69
71
72 auto reset_to_home = [&]() {
73 mj_resetData(model, data);
74 mj_kdl::set_joint_pos(&robot, q_home, false);
75 mj_forward(model, data);
76 for (unsigned i = 0; i < n; ++i) {
77 robot.jnt_pos_cmd[i] = data->qpos[robot.kdl_to_mj_qpos[i]];
78 robot.jnt_trq_cmd[i] = 0.0;
79 data->qfrc_applied[robot.kdl_to_mj_dof[i]] = 0.0;
80 }
81 mj_kdl::update(&robot);
82 };
83
84 reset_to_home();
85
86 KDL::JntArray q(n), g(n);
87 auto ctrl_step = [&]() {
88 mj_kdl::update(&robot);
89 for (unsigned i = 0; i < n; ++i) q(i) = robot.jnt_pos_msr[i];
90 dyn.JntToGravity(q, g);
91 for (unsigned i = 0; i < n; ++i) robot.jnt_trq_cmd[i] = g(i);
92 };
93
94 if (headless) {
95 KDL::Frame ee_start;
96 fk.JntToCart(q_home, ee_start);
97
98 for (int step = 0; step < 500; ++step) {
99 ctrl_step();
100 mj_kdl::step(&robot);
101 }
102
103 KDL::JntArray q_end(n);
104 for (unsigned i = 0; i < n; ++i) q_end(i) = robot.jnt_pos_msr[i];
105 KDL::Frame ee_end;
106 fk.JntToCart(q_end, ee_end);
107 double drift = (ee_start.p - ee_end.p).Norm();
108 std::cout << "EE drift after 500 steps: " << std::fixed << std::setprecision(3)
109 << drift * 1000.0 << " mm\n";
110 } else {
111 mj_kdl::Viewer viewer;
112 if (!mj_kdl::init_window_sim(&viewer, &robot)) {
113 std::cerr << "init_window_sim() failed\n";
114 mj_kdl::cleanup(&robot);
115 mj_kdl::destroy_scene(model, data);
116 return 1;
117 }
118
119 double prev_sim_time = data->time;
120 while (true) {
121 if (data->time < prev_sim_time - 1e-6) reset_to_home();
122 prev_sim_time = data->time;
123 ctrl_step();
124 if (!mj_kdl::tick(&viewer, model, data)) break;
125 }
126
127 mj_kdl::cleanup(&viewer);
128 }
129
130 mj_kdl::cleanup(&robot);
131 mj_kdl::destroy_scene(model, data);
132 return 0;
133}
int main(int argc, char *argv[])
void step(Robot *s)
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 cleanup(Robot *r)
void set_joint_pos(Robot *r, const KDL::JntArray &q, bool call_forward=true)
void update(Robot *r)
bool build_scene(mjModel **out_model, mjData **out_data, const SceneSpec *spec)
void destroy_scene(mjModel *model, mjData *data)
bool init_window_sim(Viewer *v, Robot *r, const char *title="MuJoCo")
bool tick(Viewer *v, Robot *r)
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< double > jnt_trq_cmd
std::vector< RobotSpec > robots