25static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
84int main(
int argc,
char *argv[])
86 bool headless =
false;
87 for (
int i = 1; i < argc; ++i)
88 if (std::string(argv[i]) ==
"--headless") headless =
true;
90 const fs::path root = repo_root();
91 if (!fs::exists(root /
"third_party/menagerie")) {
92 std::cerr <<
"third_party/menagerie/ not found - run:\n"
93 " cmake -B build -DFETCH_MENAGERIE=ON\n";
97 const std::string mjcf = (root /
"third_party/menagerie/kinova_gen3/gen3.xml").
string();
98 const std::string grp_mjcf = (root /
"third_party/menagerie/robotiq_2f85/2f85.xml").
string();
108 const double surface_z = sc.
table.
pos[2];
114 gs.
pos[2] = -0.061525;
118 r.
path = mjcf.c_str();
119 r.
pos[2] = surface_z;
124 make_box(
"red_cube", 0.35, 0.10, 0.03, 0.03, 0.03, 1.0f, 0.2f, 0.2f, surface_z)
127 make_box(
"green_cube", 0.35, -0.10, 0.03, 0.03, 0.03, 0.2f, 1.0f, 0.2f, surface_z)
130 make_box(
"blue_cube", 0.35, 0.30, 0.04, 0.04, 0.04, 0.2f, 0.2f, 1.0f, surface_z)
133 make_sphere(
"orange_sphere", -0.20, 0.20, 0.035, 1.0f, 0.55f, 0.0f, surface_z)
136 make_sphere(
"purple_sphere", -0.20, -0.20, 0.025, 0.7f, 0.0f, 0.9f, surface_z)
139 mjModel *model =
nullptr;
140 mjData *data =
nullptr;
143 std::cerr <<
"build_scene() failed\n";
147 &robot, model, data,
"base_link",
"bracelet_link",
"",
"g_base"
149 std::cerr <<
"init_robot_from_mjcf() failed\n";
154 unsigned n =
static_cast<unsigned>(robot.
n_joints);
155 KDL::ChainFkSolverPos_recursive fk(robot.
chain);
156 KDL::ChainDynParam dyn(robot.
chain, KDL::Vector(0.0, 0.0, sc.
gravity_z));
158 KDL::JntArray q_home(n);
159 for (
unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
161 int fingers_act = mj_name2id(model, mjOBJ_ACTUATOR,
"g_fingers_actuator");
165 auto reset_to_home = [&]() {
166 mj_resetData(model, data);
168 mj_forward(model, data);
169 for (
unsigned i = 0; i < n; ++i) {
175 if (fingers_act >= 0) data->ctrl[fingers_act] = 255.0;
180 KDL::JntArray q(n), g(n);
181 auto ctrl_step = [&]() {
183 for (
unsigned i = 0; i < n; ++i) q(i) = robot.
jnt_pos_msr[i];
184 dyn.JntToGravity(q, g);
185 for (
unsigned i = 0; i < n; ++i) robot.
jnt_trq_cmd[i] = g(i);
186 if (fingers_act >= 0)
187 data->ctrl[fingers_act] = (std::fmod(data->time, 6.0) < 3.0) ? 255.0 : 0.0;
192 fk.JntToCart(q_home, ee_start);
194 for (
int step = 0; step < 500; ++step) {
199 KDL::JntArray q_end(n);
200 for (
unsigned i = 0; i < n; ++i) q_end(i) = robot.
jnt_pos_msr[i];
202 fk.JntToCart(q_end, ee_end);
203 double drift = (ee_start.p - ee_end.p).Norm();
204 std::cout <<
"EE drift after 500 steps: " << std::fixed << std::setprecision(3)
205 << drift * 1000.0 <<
" mm\n";
209 std::cerr <<
"init_window_sim() failed\n";
215 double prev_sim_time = data->time;
217 if (data->time < prev_sim_time - 1e-6) reset_to_home();
218 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)