mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
ex_dual_arm.cpp
Go to the documentation of this file.
1/* ex_dual_arm.cpp
2 * Two Kinova Gen3 arms, each fitted with a Robotiq 2F-85 gripper,
3 * in a shared MuJoCo scene.
4 *
5 * arm1 at x = -1.5 m, facing +X.
6 * arm2 at x = +1.5 m, facing +X; all element names prefixed "r2_".
7 *
8 * Both arms hold the home pose via PD + KDL gravity compensation.
9 * Grippers cycle open/closed every 3 s.
10 *
11 * Gravity comp uses KDL::ChainDynParam built from a chain that includes
12 * the gripper's lumped inertia (via init_robot_from_mjcf tool_body).
13 * jnt_trq_cmd is primed before the loop so the first physics step already
14 * gets correct compensation.
15 *
16 * Requires third_party/menagerie submodule.
17 *
18 * Usage:
19 * ex_dual_arm [--headless]
20 *
21 * --headless: run 600 steps and print both EE positions, then exit. */
22
24
25#include <kdl/chaindynparam.hpp>
26#include <kdl/chainfksolverpos_recursive.hpp>
27
28#include <cmath>
29#include <filesystem>
30#include <iostream>
31#include <string>
32
33static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
34
35static constexpr double kKp[7] = { 100, 200, 100, 200, 100, 200, 100 };
36static constexpr double kKd[7] = { 10, 20, 10, 20, 10, 20, 10 };
37
38namespace fs = std::filesystem;
39static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path().parent_path(); }
40
41int main(int argc, char *argv[])
42{
43 bool headless = false;
44 for (int i = 1; i < argc; ++i)
45 if (std::string(argv[i]) == "--headless") headless = true;
46
47 const fs::path root = repo_root();
48 if (!fs::exists(root / "third_party/menagerie")) {
49 std::cerr << "third_party/menagerie/ not found - run:\n"
50 " git submodule update --init third_party/menagerie\n";
51 return 1;
52 }
53
54 const std::string arm_mjcf = (root / "third_party/menagerie/kinova_gen3/gen3.xml").string();
55 const std::string grp_mjcf = (root / "third_party/menagerie/robotiq_2f85/2f85.xml").string();
56
58 gs.mjcf_path = grp_mjcf.c_str();
59 gs.attach_to = "bracelet_link";
60 gs.prefix = "g_";
61 gs.pos[2] = -0.061525;
62 gs.euler[0] = 180.0; // 180 deg around X to flip gripper
63
64 mj_kdl::RobotSpec arm1_spec;
65 arm1_spec.path = arm_mjcf.c_str();
66 arm1_spec.prefix = "";
67 arm1_spec.pos[0] = -1.0;
68 arm1_spec.attachments.push_back(gs);
69
70 mj_kdl::RobotSpec arm2_spec;
71 arm2_spec.path = arm_mjcf.c_str();
72 arm2_spec.prefix = "r2_";
73 arm2_spec.pos[0] = 1.0;
74 arm2_spec.attachments.push_back(gs);
75
77 sc.robots.push_back(arm1_spec);
78 sc.robots.push_back(arm2_spec);
79
80 mjModel *model = nullptr;
81 mjData *data = nullptr;
82 if (!mj_kdl::build_scene(&model, &data, &sc)) {
83 std::cerr << "build_scene() failed\n";
84 return 1;
85 }
86
87 mj_kdl::Robot arm1, arm2;
88 if (
89 !mj_kdl::init_robot_from_mjcf(&arm1, model, data, "base_link", "bracelet_link", "", "g_base")
91 &arm2, model, data, "r2_base_link", "r2_bracelet_link", "", "r2_g_base"
92 )
93 ) {
94 std::cerr << "init_robot_from_mjcf() failed\n";
95 mj_kdl::destroy_scene(model, data);
96 return 1;
97 }
98
99 const int n = arm1.n_joints;
100 int fing1 = mj_name2id(model, mjOBJ_ACTUATOR, "g_fingers_actuator");
101 int fing2 = mj_name2id(model, mjOBJ_ACTUATOR, "r2_g_fingers_actuator");
102
103 KDL::ChainDynParam dyn1(arm1.chain, KDL::Vector(0.0, 0.0, -9.81));
104 KDL::ChainDynParam dyn2(arm2.chain, KDL::Vector(0.0, 0.0, -9.81));
105
106 KDL::JntArray q_home(n), q1(n), q2(n), g1(n), g2(n);
107 for (int i = 0; i < n; ++i) q_home(i) = kHomePose[i];
110
111 // Prime jnt_trq_cmd so the first physics step already gets gravity compensation.
112 auto prime_grav = [&]() {
113 dyn1.JntToGravity(q_home, g1);
114 dyn2.JntToGravity(q_home, g2);
115 for (int i = 0; i < n; ++i) {
116 arm1.jnt_trq_cmd[i] = g1(i);
117 arm2.jnt_trq_cmd[i] = g2(i);
118 }
119 };
120
121 auto reset_to_home = [&]() {
122 mj_resetData(model, data);
123 mj_kdl::set_joint_pos(&arm1, q_home, false);
124 mj_kdl::set_joint_pos(&arm2, q_home, false);
125 mj_forward(model, data);
126 for (int i = 0; i < n; ++i) {
127 arm1.jnt_pos_cmd[i] = data->qpos[arm1.kdl_to_mj_qpos[i]];
128 arm2.jnt_pos_cmd[i] = data->qpos[arm2.kdl_to_mj_qpos[i]];
129 data->qfrc_applied[arm1.kdl_to_mj_dof[i]] = 0.0;
130 data->qfrc_applied[arm2.kdl_to_mj_dof[i]] = 0.0;
131 }
132 prime_grav();
133 mj_kdl::update(&arm1);
134 mj_kdl::update(&arm2);
135 if (fing1 >= 0) data->ctrl[fing1] = 255.0;
136 if (fing2 >= 0) data->ctrl[fing2] = 255.0;
137 };
138
139 reset_to_home();
140
141 // Per-step: update() reads sensors and flushes the previous jnt_trq_cmd;
142 // then compute PD + KDL gravity for the next step.
143 auto ctrl_step = [&]() {
144 mj_kdl::update(&arm1);
145 mj_kdl::update(&arm2);
146 for (int i = 0; i < n; ++i) q1(i) = arm1.jnt_pos_msr[i];
147 for (int i = 0; i < n; ++i) q2(i) = arm2.jnt_pos_msr[i];
148 dyn1.JntToGravity(q1, g1);
149 dyn2.JntToGravity(q2, g2);
150 for (int i = 0; i < n; ++i) {
151 arm1.jnt_trq_cmd[i] =
152 kKp[i] * (kHomePose[i] - arm1.jnt_pos_msr[i]) - kKd[i] * arm1.jnt_vel_msr[i] + g1(i);
153 arm2.jnt_trq_cmd[i] =
154 kKp[i] * (kHomePose[i] - arm2.jnt_pos_msr[i]) - kKd[i] * arm2.jnt_vel_msr[i] + g2(i);
155 }
156 if (fing1 >= 0) data->ctrl[fing1] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
157 if (fing2 >= 0) data->ctrl[fing2] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
158 };
159
160 if (headless) {
161 for (int step = 0; step < 600; ++step) {
162 ctrl_step();
163 mj_kdl::step(&arm1);
164 }
165
166 KDL::ChainFkSolverPos_recursive fk1(arm1.chain), fk2(arm2.chain);
167 KDL::JntArray q1(n), q2(n);
168 KDL::Frame ee1, ee2;
169 for (int i = 0; i < n; ++i) {
170 q1(i) = arm1.jnt_pos_msr[i];
171 q2(i) = arm2.jnt_pos_msr[i];
172 }
173 fk1.JntToCart(q1, ee1);
174 fk2.JntToCart(q2, ee2);
175 std::cout << "arm1 EE: [" << ee1.p.x() << ", " << ee1.p.y() << ", " << ee1.p.z() << "]\n";
176 std::cout << "arm2 EE: [" << ee2.p.x() << ", " << ee2.p.y() << ", " << ee2.p.z() << "]\n";
177 } else {
178 mj_kdl::Viewer viewer;
179 if (!mj_kdl::init_window_sim(&viewer, &arm1)) {
180 std::cerr << "init_window_sim() failed\n";
181 mj_kdl::cleanup(&arm1);
182 mj_kdl::cleanup(&arm2);
183 mj_kdl::destroy_scene(model, data);
184 return 1;
185 }
186
187 double prev_sim_time = data->time;
188 while (true) {
189 if (data->time < prev_sim_time - 1e-6) reset_to_home();
190 prev_sim_time = data->time;
191 ctrl_step();
192 if (!mj_kdl::tick(&viewer, model, data)) break;
193 }
194
195 mj_kdl::cleanup(&viewer);
196 }
197
198 mj_kdl::cleanup(&arm1);
199 mj_kdl::cleanup(&arm2);
200 mj_kdl::destroy_scene(model, data);
201 return 0;
202}
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< AttachmentSpec > attachments
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_vel_msr
std::vector< double > jnt_trq_cmd
std::vector< RobotSpec > robots