mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
ex_table_scene.cpp
Go to the documentation of this file.
1/* ex_table_scene.cpp (MJCF)
2 * Kinova GEN3 + Robotiq 2F-85 gripper on a table with a few free objects,
3 * loaded from MuJoCo Menagerie MJCF.
4 *
5 * The arm runs KDL gravity compensation; the gripper cycles open/closed every 3 s.
6 *
7 * Requires third_party/menagerie submodule.
8 *
9 * Usage:
10 * ex_table_scene_mjcf [--headless]
11 *
12 * With --headless runs 500 steps and prints final EE drift. */
13
15
16#include <kdl/chaindynparam.hpp>
17#include <kdl/chainfksolverpos_recursive.hpp>
18
19#include <cmath>
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
30static mj_kdl::SceneObject make_box(
31 const char *name,
32 double x,
33 double y,
34 double hx,
35 double hy,
36 double hz,
37 float r,
38 float g,
39 float b,
40 double surface_z
41)
42{
44 o.name = name;
46 o.size[0] = hx;
47 o.size[1] = hy;
48 o.size[2] = hz;
49 o.pos[0] = x;
50 o.pos[1] = y;
51 o.pos[2] = surface_z + hz;
52 o.rgba[0] = r;
53 o.rgba[1] = g;
54 o.rgba[2] = b;
55 o.rgba[3] = 1.0f;
56 return o;
57}
58
59static mj_kdl::SceneObject make_sphere(
60 const char *name,
61 double x,
62 double y,
63 double radius,
64 float r,
65 float g,
66 float b,
67 double surface_z
68)
69{
71 o.name = name;
73 o.size[0] = radius;
74 o.pos[0] = x;
75 o.pos[1] = y;
76 o.pos[2] = surface_z + radius;
77 o.rgba[0] = r;
78 o.rgba[1] = g;
79 o.rgba[2] = b;
80 o.rgba[3] = 1.0f;
81 return o;
82}
83
84int main(int argc, char *argv[])
85{
86 bool headless = false;
87 for (int i = 1; i < argc; ++i)
88 if (std::string(argv[i]) == "--headless") headless = true;
89
90 const fs::path root = repo_root();
91 if (!fs::exists(root / "third_party/menagerie")) {
92 std::cerr << "third_party/menagerie/ not found - run:\n"
93 " cmake -B build -DFETCH_MENAGERIE=ON\n";
94 return 1;
95 }
96
97 const std::string mjcf = (root / "third_party/menagerie/kinova_gen3/gen3.xml").string();
98 const std::string grp_mjcf = (root / "third_party/menagerie/robotiq_2f85/2f85.xml").string();
99
101 sc.table.enabled = true;
102 sc.table.pos[2] = 0.7;
103 sc.table.top_size[0] = 0.8;
104 sc.table.top_size[1] = 0.6;
105 sc.table.thickness = 0.04;
106 sc.table.leg_radius = 0.03;
107
108 const double surface_z = sc.table.pos[2];
109
111 gs.mjcf_path = grp_mjcf.c_str();
112 gs.attach_to = "bracelet_link";
113 gs.prefix = "g_";
114 gs.pos[2] = -0.061525;
115 gs.euler[0] = 180.0;
116
118 r.path = mjcf.c_str();
119 r.pos[2] = surface_z;
120 r.attachments.push_back(gs);
121 sc.robots.push_back(r);
122
123 sc.objects.push_back(
124 make_box("red_cube", 0.35, 0.10, 0.03, 0.03, 0.03, 1.0f, 0.2f, 0.2f, surface_z)
125 );
126 sc.objects.push_back(
127 make_box("green_cube", 0.35, -0.10, 0.03, 0.03, 0.03, 0.2f, 1.0f, 0.2f, surface_z)
128 );
129 sc.objects.push_back(
130 make_box("blue_cube", 0.35, 0.30, 0.04, 0.04, 0.04, 0.2f, 0.2f, 1.0f, surface_z)
131 );
132 sc.objects.push_back(
133 make_sphere("orange_sphere", -0.20, 0.20, 0.035, 1.0f, 0.55f, 0.0f, surface_z)
134 );
135 sc.objects.push_back(
136 make_sphere("purple_sphere", -0.20, -0.20, 0.025, 0.7f, 0.0f, 0.9f, surface_z)
137 );
138
139 mjModel *model = nullptr;
140 mjData *data = nullptr;
141 mj_kdl::Robot robot;
142 if (!mj_kdl::build_scene(&model, &data, &sc)) {
143 std::cerr << "build_scene() failed\n";
144 return 1;
145 }
147 &robot, model, data, "base_link", "bracelet_link", "", "g_base"
148 )) {
149 std::cerr << "init_robot_from_mjcf() failed\n";
150 mj_kdl::destroy_scene(model, data);
151 return 1;
152 }
153
154 unsigned n = static_cast<unsigned>(robot.n_joints);
155 KDL::ChainFkSolverPos_recursive fk(robot.chain);
156 KDL::ChainDynParam dyn(robot.chain, KDL::Vector(0.0, 0.0, sc.gravity_z));
157
158 KDL::JntArray q_home(n);
159 for (unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
160
161 int fingers_act = mj_name2id(model, mjOBJ_ACTUATOR, "g_fingers_actuator");
162
164
165 auto reset_to_home = [&]() {
166 mj_resetData(model, data);
167 mj_kdl::set_joint_pos(&robot, q_home, false);
168 mj_forward(model, data);
169 for (unsigned i = 0; i < n; ++i) {
170 robot.jnt_pos_cmd[i] = data->qpos[robot.kdl_to_mj_qpos[i]];
171 robot.jnt_trq_cmd[i] = 0.0;
172 data->qfrc_applied[robot.kdl_to_mj_dof[i]] = 0.0;
173 }
174 mj_kdl::update(&robot);
175 if (fingers_act >= 0) data->ctrl[fingers_act] = 255.0;
176 };
177
178 reset_to_home();
179
180 KDL::JntArray q(n), g(n);
181 auto ctrl_step = [&]() {
182 mj_kdl::update(&robot);
183 for (unsigned i = 0; i < n; ++i) q(i) = robot.jnt_pos_msr[i];
184 dyn.JntToGravity(q, g);
185 for (unsigned i = 0; i < n; ++i) robot.jnt_trq_cmd[i] = g(i);
186 if (fingers_act >= 0)
187 data->ctrl[fingers_act] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
188 };
189
190 if (headless) {
191 KDL::Frame ee_start;
192 fk.JntToCart(q_home, ee_start);
193
194 for (int step = 0; step < 500; ++step) {
195 ctrl_step();
196 mj_kdl::step(&robot);
197 }
198
199 KDL::JntArray q_end(n);
200 for (unsigned i = 0; i < n; ++i) q_end(i) = robot.jnt_pos_msr[i];
201 KDL::Frame ee_end;
202 fk.JntToCart(q_end, ee_end);
203 double drift = (ee_start.p - ee_end.p).Norm();
204 std::cout << "EE drift after 500 steps: " << std::fixed << std::setprecision(3)
205 << drift * 1000.0 << " mm\n";
206 } else {
207 mj_kdl::Viewer viewer;
208 if (!mj_kdl::init_window_sim(&viewer, &robot)) {
209 std::cerr << "init_window_sim() failed\n";
210 mj_kdl::cleanup(&robot);
211 mj_kdl::destroy_scene(model, data);
212 return 1;
213 }
214
215 double prev_sim_time = data->time;
216 while (true) {
217 if (data->time < prev_sim_time - 1e-6) reset_to_home();
218 prev_sim_time = data->time;
219 ctrl_step();
220 if (!mj_kdl::tick(&viewer, model, data)) break;
221 }
222
223 mj_kdl::cleanup(&viewer);
224 }
225
226 mj_kdl::cleanup(&robot);
227 mj_kdl::destroy_scene(model, data);
228 return 0;
229}
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_trq_cmd
std::vector< RobotSpec > robots
std::vector< SceneObject > objects