mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
ex_gripper.cpp
Go to the documentation of this file.
1/* ex_gripper.cpp
2 * Attach a Robotiq 2F-85 gripper to the Kinova GEN3 and run KDL gravity
3 * compensation. The gripper cycles open and closed every 3 s.
4 *
5 * Requires third_party/menagerie (MuJoCo Menagerie submodule).
6 *
7 * Usage:
8 * ex_gripper [--headless]
9 *
10 * With --headless runs 300 steps and prints elapsed sim time. */
11
13
14#include <kdl/chaindynparam.hpp>
15
16#include <cmath>
17#include <filesystem>
18#include <iostream>
19#include <string>
20
21static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
22
23
24namespace fs = std::filesystem;
25static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path().parent_path(); }
26
27int main(int argc, char *argv[])
28{
29 bool headless = false;
30 for (int i = 1; i < argc; ++i)
31 if (std::string(argv[i]) == "--headless") headless = true;
32
33 const fs::path root = repo_root();
34 if (!fs::exists(root / "third_party/menagerie")) {
35 std::cerr << "third_party/menagerie/ not found - run: "
36 "git submodule update --init third_party/menagerie\n";
37 return 1;
38 }
39
40 const std::string arm_mjcf = (root / "third_party/menagerie/kinova_gen3/gen3.xml").string();
41 const std::string grp_mjcf = (root / "third_party/menagerie/robotiq_2f85/2f85.xml").string();
42
44 gs.mjcf_path = grp_mjcf.c_str();
45 gs.attach_to = "bracelet_link";
46 gs.prefix = "g_";
47 gs.pos[2] = -0.061525;
48 gs.euler[0] = 180.0; // 180 deg around X to flip gripper
49
51 rs.path = arm_mjcf.c_str();
52 rs.attachments.push_back(gs);
53
55 sc.robots.push_back(rs);
56
57 mjModel *model = nullptr;
58 mjData *data = nullptr;
59 if (!mj_kdl::build_scene(&model, &data, &sc)) {
60 std::cerr << "build_scene() failed\n";
61 return 1;
62 }
63
64 mj_kdl::Robot robot;
66 &robot, model, data, "base_link", "bracelet_link", "", "g_base"
67 )) {
68 std::cerr << "init_robot_from_mjcf() failed\n";
69 mj_kdl::destroy_scene(model, data);
70 return 1;
71 }
72
73 unsigned n = robot.chain.getNrOfJoints();
74 int fingers_act = mj_name2id(model, mjOBJ_ACTUATOR, "g_fingers_actuator");
75 int key_id = mj_name2id(model, mjOBJ_KEY, "home");
76
78
79 KDL::ChainDynParam dyn(robot.chain, KDL::Vector(0.0, 0.0, -9.81));
80 KDL::JntArray q_home(n), q(n), g(n);
81 for (unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
82
83 auto reset_to_home = [&]() {
84 if (key_id >= 0) {
85 mj_resetDataKeyframe(model, data, key_id);
86 } else {
87 mj_resetData(model, data);
88 mj_kdl::set_joint_pos(&robot, q_home, false);
89 }
90 mj_forward(model, data);
91 for (unsigned i = 0; i < n; ++i) {
92 robot.jnt_pos_cmd[i] = data->qpos[robot.kdl_to_mj_qpos[i]];
93 robot.jnt_trq_cmd[i] = 0.0;
94 data->qfrc_applied[robot.kdl_to_mj_dof[i]] = 0.0;
95 }
96 mj_kdl::update(&robot);
97 if (fingers_act >= 0) data->ctrl[fingers_act] = 255.0;
98 };
99
100 reset_to_home();
101
102 auto ctrl_step = [&]() {
103 mj_kdl::update(&robot);
104 for (unsigned i = 0; i < n; ++i) q(i) = robot.jnt_pos_msr[i];
105 dyn.JntToGravity(q, g);
106 for (unsigned i = 0; i < n; ++i) robot.jnt_trq_cmd[i] = g(i);
107 data->ctrl[fingers_act] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
108 };
109
110 if (headless) {
111 for (int step = 0; step < 300; ++step) {
112 ctrl_step();
113 mj_kdl::step(&robot);
114 }
115 std::cout << "sim_time=" << data->time << " s\n";
116 } else {
117 mj_kdl::Viewer viewer;
118 if (!mj_kdl::init_window_sim(&viewer, &robot)) {
119 std::cerr << "init_window_sim() failed\n";
120 mj_kdl::cleanup(&robot);
121 mj_kdl::destroy_scene(model, data);
122 return 1;
123 }
124
125 double prev_sim_time = data->time;
126 while (true) {
127 if (data->time < prev_sim_time - 1e-6) reset_to_home();
128 prev_sim_time = data->time;
129 ctrl_step();
130 if (!mj_kdl::tick(&viewer, model, data)) break;
131 }
132
133 mj_kdl::cleanup(&viewer);
134 }
135
136 mj_kdl::cleanup(&robot);
137 mj_kdl::destroy_scene(model, data);
138 return 0;
139}
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