mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
ex_pos_ctrl.cpp
Go to the documentation of this file.
1/* ex_pos_ctrl.cpp (MJCF)
2 * Joint position control: drive the Kinova GEN3 from the home pose to a target
3 * pose using linearly interpolated position setpoints, then hold.
4 *
5 * The setpoint trajectory is a straight-line interpolation in joint space over
6 * kMotionDuration seconds. After the motion completes the final position is
7 * held indefinitely.
8 *
9 * Requires third_party/menagerie submodule.
10 *
11 * Usage:
12 * ex_pos_ctrl [--headless]
13 *
14 * With --headless runs the full motion and prints final max joint error. */
15
17
18#include <algorithm>
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 };
26static constexpr double kTargetPose[7] = { 0.3, 0.5, 2.9, -2.0, 0.3, 1.2, 1.3 };
27static constexpr double kMotionDuration = 2.0; // seconds for the interpolated move
28
29namespace fs = std::filesystem;
30static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path().parent_path(); }
31
32int main(int argc, char *argv[])
33{
34 bool headless = false;
35 for (int i = 1; i < argc; ++i)
36 if (std::string(argv[i]) == "--headless") headless = true;
37
38 const fs::path root = repo_root();
39 if (!fs::exists(root / "third_party/menagerie")) {
40 std::cerr << "third_party/menagerie/ not found - run:\n"
41 " cmake -B build -DFETCH_MENAGERIE=ON\n";
42 return 1;
43 }
44
45 const std::string mjcf = (root / "third_party/menagerie/kinova_gen3/gen3.xml").string();
46
49 r.path = mjcf.c_str();
50 sc.robots.push_back(r);
51
52 mjModel *model = nullptr;
53 mjData *data = nullptr;
54 if (!mj_kdl::build_scene(&model, &data, &sc)) {
55 std::cerr << "build_scene() failed\n";
56 return 1;
57 }
58
59 mj_kdl::Robot robot;
60 if (!mj_kdl::init_robot_from_mjcf(&robot, model, data, "base_link", "bracelet_link")) {
61 std::cerr << "init_robot_from_mjcf() failed\n";
62 mj_kdl::destroy_scene(model, data);
63 return 1;
64 }
65
66 unsigned n = static_cast<unsigned>(robot.n_joints);
67
68 KDL::JntArray q_home(n);
69 for (unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
70
72
73 double t_start = 0.0;
74
75 auto reset_to_home = [&]() {
76 mj_resetData(model, data);
77 mj_kdl::set_joint_pos(&robot, q_home, false);
78 mj_forward(model, data);
79 t_start = data->time;
80 for (unsigned i = 0; i < n; ++i) { robot.jnt_pos_cmd[i] = kHomePose[i]; }
81 mj_kdl::update(&robot);
82 };
83
84 reset_to_home();
85
86 auto ctrl_step = [&]() {
87 mj_kdl::update(&robot);
88
89 double alpha = std::clamp((data->time - t_start) / kMotionDuration, 0.0, 1.0);
90 for (unsigned i = 0; i < n; ++i)
91 robot.jnt_pos_cmd[i] = kHomePose[i] + alpha * (kTargetPose[i] - kHomePose[i]);
92 };
93
94 if (headless) {
95 // Run until the trajectory is complete plus a short settling period.
96 const double end_time = kMotionDuration + 1.0;
97 while (data->time < end_time) {
98 ctrl_step();
99 mj_kdl::step(&robot);
100 }
101
102 double max_err = 0.0;
103 for (unsigned i = 0; i < n; ++i)
104 max_err = std::max(max_err, std::abs(kTargetPose[i] - robot.jnt_pos_msr[i]));
105 std::cout << "max joint error at end: " << std::fixed << std::setprecision(4) << max_err
106 << " rad\n";
107 } else {
108 mj_kdl::Viewer viewer;
109 if (!mj_kdl::init_window_sim(&viewer, &robot)) {
110 std::cerr << "init_window_sim() failed\n";
111 mj_kdl::cleanup(&robot);
112 mj_kdl::destroy_scene(model, data);
113 return 1;
114 }
115
116 double prev_sim_time = data->time;
117 while (true) {
118 if (data->time < prev_sim_time - 1e-6) reset_to_home();
119 prev_sim_time = data->time;
120 ctrl_step();
121 if (!mj_kdl::tick(&viewer, model, data)) break;
122 }
123
124 mj_kdl::cleanup(&viewer);
125 }
126
127 mj_kdl::cleanup(&robot);
128 mj_kdl::destroy_scene(model, data);
129 return 0;
130}
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< double > jnt_pos_msr
std::vector< double > jnt_pos_cmd
std::vector< RobotSpec > robots