21static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
27int main(
int argc,
char *argv[])
29 bool headless =
false;
30 for (
int i = 1; i < argc; ++i)
31 if (std::string(argv[i]) ==
"--headless") headless =
true;
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";
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();
47 gs.
pos[2] = -0.061525;
51 rs.
path = arm_mjcf.c_str();
57 mjModel *model =
nullptr;
58 mjData *data =
nullptr;
60 std::cerr <<
"build_scene() failed\n";
66 &robot, model, data,
"base_link",
"bracelet_link",
"",
"g_base"
68 std::cerr <<
"init_robot_from_mjcf() failed\n";
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");
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];
83 auto reset_to_home = [&]() {
85 mj_resetDataKeyframe(model, data, key_id);
87 mj_resetData(model, data);
90 mj_forward(model, data);
91 for (
unsigned i = 0; i < n; ++i) {
97 if (fingers_act >= 0) data->ctrl[fingers_act] = 255.0;
102 auto ctrl_step = [&]() {
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;
111 for (
int step = 0; step < 300; ++step) {
115 std::cout <<
"sim_time=" << data->time <<
" s\n";
119 std::cerr <<
"init_window_sim() failed\n";
125 double prev_sim_time = data->time;
127 if (data->time < prev_sim_time - 1e-6) reset_to_home();
128 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)