mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
test_mjcf_pos_ctrl.cpp
Go to the documentation of this file.
1/* test_mjcf_pos_ctrl.cpp
2 * Joint position control on the Kinova GEN3 (MJCF).
3 *
4 * gen3.xml has high-gain position actuators (kp=2000, kv=100).
5 * CtrlMode::POSITION writes the target joint position directly to ctrl[],
6 * and the built-in servo drives the joint to that position.
7 *
8 * Uses a linearly interpolated trajectory from home to a nearby target pose. */
9
11#include "test_utils.hpp"
12
13#include <gtest/gtest.h>
14
15#include <algorithm>
16#include <cmath>
17#include <filesystem>
18#include <iomanip>
19#include <iostream>
20#include <string>
21
22static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
23static constexpr double kTargetPose[7] = { 0.3, 0.5, 2.9, -2.0, 0.3, 1.2, 1.3 };
24static constexpr double kMotionDuration = 1.5; // s - linear interp from home to target
25static constexpr double kSettleTime = 0.5; // s - extra time to let servo settle
26static constexpr double kErrTol = 0.05; // rad
27
28namespace fs = std::filesystem;
29static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path(); }
30
31class MjcfPosCtrlTest : public testing::Test
32{
33 protected:
34 fs::path root_;
35 mjModel *model_ = nullptr;
36 mjData *data_ = nullptr;
38 unsigned n_ = 0;
39
40 void SetUp() override
41 {
42 root_ = repo_root();
43 if (!fs::exists(root_ / "third_party/menagerie")) {
44 GTEST_SKIP() << "third_party/menagerie/ not found";
45 return;
46 }
47
48 std::string arm_mjcf = (root_ / "third_party/menagerie/kinova_gen3/gen3.xml").string();
49
52 r.path = arm_mjcf.c_str();
53 sc.robots.push_back(r);
54
55 ASSERT_TRUE(mj_kdl::build_scene(&model_, &data_, &sc));
56 ASSERT_TRUE(mj_kdl::init_robot_from_mjcf(&s_, model_, data_, "base_link", "bracelet_link"));
57
58 n_ = static_cast<unsigned>(s_.n_joints);
59
60 KDL::JntArray q_home(n_);
61 for (unsigned i = 0; i < n_; ++i) q_home(i) = kHomePose[i];
62 mj_kdl::set_joint_pos(&s_, q_home, false);
63 mj_forward(model_, data_);
64
66 for (unsigned i = 0; i < n_; ++i) { s_.jnt_pos_cmd[i] = kHomePose[i]; }
68 }
69
70 void TearDown() override
71 {
72 if (model_) {
75 }
76 }
77};
78
79TEST_F(MjcfPosCtrlTest, TrajectoryTracking)
80{
81 const double t_start = data_->time;
82 const double t_end = t_start + kMotionDuration + kSettleTime;
83
84 while (data_->time < t_end) {
85 mj_kdl::update(&s_);
86 double alpha = std::clamp((data_->time - t_start) / kMotionDuration, 0.0, 1.0);
87 for (unsigned i = 0; i < n_; ++i)
88 s_.jnt_pos_cmd[i] = kHomePose[i] + alpha * (kTargetPose[i] - kHomePose[i]);
89 mj_kdl::step(&s_);
90 }
91
92 double max_err = 0.0;
93 for (unsigned i = 0; i < n_; ++i)
94 max_err = std::max(max_err, std::abs(kTargetPose[i] - s_.jnt_pos_msr[i]));
95
97 "MJCF position ctrl max joint error after "
98 << (kMotionDuration + kSettleTime) << " s: " << std::fixed << std::setprecision(4) << max_err
99 << " rad"
100 );
101 EXPECT_LE(max_err, kErrTol);
102}
103
104int main(int argc, char *argv[])
105{
106 testing::InitGoogleTest(&argc, argv);
107 return RUN_ALL_TESTS();
108}
void SetUp() override
void TearDown() override
void step(Robot *s)
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 cleanup(Robot *r)
void set_joint_pos(Robot *r, const KDL::JntArray &q, bool call_forward=true)
void update(Robot *r)
bool build_scene(mjModel **out_model, mjData **out_data, const SceneSpec *spec)
void destroy_scene(mjModel *model, mjData *data)
std::vector< double > jnt_pos_cmd
std::vector< RobotSpec > robots
int main(int argc, char *argv[])
TEST_F(MjcfPosCtrlTest, TrajectoryTracking)
#define TEST_INFO(msg)