33static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
35static constexpr double kKp[7] = { 100, 200, 100, 200, 100, 200, 100 };
36static constexpr double kKd[7] = { 10, 20, 10, 20, 10, 20, 10 };
41int main(
int argc,
char *argv[])
43 bool headless =
false;
44 for (
int i = 1; i < argc; ++i)
45 if (std::string(argv[i]) ==
"--headless") headless =
true;
47 const fs::path root = repo_root();
48 if (!fs::exists(root /
"third_party/menagerie")) {
49 std::cerr <<
"third_party/menagerie/ not found - run:\n"
50 " git submodule update --init third_party/menagerie\n";
54 const std::string arm_mjcf = (root /
"third_party/menagerie/kinova_gen3/gen3.xml").
string();
55 const std::string grp_mjcf = (root /
"third_party/menagerie/robotiq_2f85/2f85.xml").
string();
61 gs.
pos[2] = -0.061525;
65 arm1_spec.
path = arm_mjcf.c_str();
67 arm1_spec.
pos[0] = -1.0;
71 arm2_spec.
path = arm_mjcf.c_str();
73 arm2_spec.
pos[0] = 1.0;
77 sc.
robots.push_back(arm1_spec);
78 sc.
robots.push_back(arm2_spec);
80 mjModel *model =
nullptr;
81 mjData *data =
nullptr;
83 std::cerr <<
"build_scene() failed\n";
91 &arm2, model, data,
"r2_base_link",
"r2_bracelet_link",
"",
"r2_g_base"
94 std::cerr <<
"init_robot_from_mjcf() failed\n";
100 int fing1 = mj_name2id(model, mjOBJ_ACTUATOR,
"g_fingers_actuator");
101 int fing2 = mj_name2id(model, mjOBJ_ACTUATOR,
"r2_g_fingers_actuator");
103 KDL::ChainDynParam dyn1(arm1.
chain, KDL::Vector(0.0, 0.0, -9.81));
104 KDL::ChainDynParam dyn2(arm2.
chain, KDL::Vector(0.0, 0.0, -9.81));
106 KDL::JntArray q_home(n), q1(n), q2(n), g1(n), g2(n);
107 for (
int i = 0; i < n; ++i) q_home(i) = kHomePose[i];
112 auto prime_grav = [&]() {
113 dyn1.JntToGravity(q_home, g1);
114 dyn2.JntToGravity(q_home, g2);
115 for (
int i = 0; i < n; ++i) {
121 auto reset_to_home = [&]() {
122 mj_resetData(model, data);
125 mj_forward(model, data);
126 for (
int i = 0; i < n; ++i) {
135 if (fing1 >= 0) data->ctrl[fing1] = 255.0;
136 if (fing2 >= 0) data->ctrl[fing2] = 255.0;
143 auto ctrl_step = [&]() {
146 for (
int i = 0; i < n; ++i) q1(i) = arm1.
jnt_pos_msr[i];
147 for (
int i = 0; i < n; ++i) q2(i) = arm2.
jnt_pos_msr[i];
148 dyn1.JntToGravity(q1, g1);
149 dyn2.JntToGravity(q2, g2);
150 for (
int i = 0; i < n; ++i) {
156 if (fing1 >= 0) data->ctrl[fing1] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
157 if (fing2 >= 0) data->ctrl[fing2] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
161 for (
int step = 0; step < 600; ++step) {
166 KDL::ChainFkSolverPos_recursive fk1(arm1.
chain), fk2(arm2.
chain);
167 KDL::JntArray q1(n), q2(n);
169 for (
int i = 0; i < n; ++i) {
173 fk1.JntToCart(q1, ee1);
174 fk2.JntToCart(q2, ee2);
175 std::cout <<
"arm1 EE: [" << ee1.p.x() <<
", " << ee1.p.y() <<
", " << ee1.p.z() <<
"]\n";
176 std::cout <<
"arm2 EE: [" << ee2.p.x() <<
", " << ee2.p.y() <<
", " << ee2.p.z() <<
"]\n";
180 std::cerr <<
"init_window_sim() failed\n";
187 double prev_sim_time = data->time;
189 if (data->time < prev_sim_time - 1e-6) reset_to_home();
190 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)