25static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
30int main(
int argc,
char *argv[])
32 bool headless =
false;
33 for (
int i = 1; i < argc; ++i)
34 if (std::string(argv[i]) ==
"--headless") headless =
true;
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";
43 const std::string mjcf = (root /
"third_party/menagerie/kinova_gen3/gen3.xml").
string();
47 r.
path = mjcf.c_str();
50 mjModel *model =
nullptr;
51 mjData *data =
nullptr;
54 std::cerr <<
"build_scene() failed\n";
58 std::cerr <<
"init_robot_from_mjcf() failed\n";
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));
67 KDL::JntArray q_home(n);
68 for (
unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
72 auto reset_to_home = [&]() {
73 mj_resetData(model, data);
75 mj_forward(model, data);
76 for (
unsigned i = 0; i < n; ++i) {
86 KDL::JntArray q(n), g(n);
87 auto ctrl_step = [&]() {
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);
96 fk.JntToCart(q_home, ee_start);
98 for (
int step = 0; step < 500; ++step) {
103 KDL::JntArray q_end(n);
104 for (
unsigned i = 0; i < n; ++i) q_end(i) = robot.
jnt_pos_msr[i];
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";
113 std::cerr <<
"init_window_sim() failed\n";
119 double prev_sim_time = data->time;
121 if (data->time < prev_sim_time - 1e-6) reset_to_home();
122 prev_sim_time = data->time;
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)