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;
29namespace fs = std::filesystem;
30static fs::path repo_root() {
return fs::path(__FILE__).parent_path().parent_path().parent_path(); }
32int main(
int argc,
char *argv[])
34 bool headless =
false;
35 for (
int i = 1; i < argc; ++i)
36 if (std::string(argv[i]) ==
"--headless") headless =
true;
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";
45 const std::string mjcf = (root /
"third_party/menagerie/kinova_gen3/gen3.xml").
string();
49 r.
path = mjcf.c_str();
52 mjModel *model =
nullptr;
53 mjData *data =
nullptr;
55 std::cerr <<
"build_scene() failed\n";
61 std::cerr <<
"init_robot_from_mjcf() failed\n";
66 unsigned n =
static_cast<unsigned>(robot.
n_joints);
68 KDL::JntArray q_home(n);
69 for (
unsigned i = 0; i < n; ++i) q_home(i) = kHomePose[i];
75 auto reset_to_home = [&]() {
76 mj_resetData(model, data);
78 mj_forward(model, data);
80 for (
unsigned i = 0; i < n; ++i) { robot.
jnt_pos_cmd[i] = kHomePose[i]; }
86 auto ctrl_step = [&]() {
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]);
96 const double end_time = kMotionDuration + 1.0;
97 while (data->time < end_time) {
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
110 std::cerr <<
"init_window_sim() failed\n";
116 double prev_sim_time = data->time;
118 if (data->time < prev_sim_time - 1e-6) reset_to_home();
119 prev_sim_time = data->time;
int main(int argc, char *argv[])
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 set_joint_pos(Robot *r, const KDL::JntArray &q, bool call_forward=true)
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