mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
test_mjcf_trq_ctrl.cpp
Go to the documentation of this file.
1/* test_mjcf_trq_ctrl.cpp
2 * Torque-mode control on the Kinova GEN3 + Robotiq 2F-85 (MJCF). */
3
5#include "test_utils.hpp"
6
7#include <gtest/gtest.h>
8
9#include <kdl/chaindynparam.hpp>
10#include <kdl/chainfksolverpos_recursive.hpp>
11
12#include <algorithm>
13#include <cmath>
14#include <filesystem>
15#include <iomanip>
16#include <iostream>
17#include <memory>
18#include <string>
19
20namespace fs = std::filesystem;
21
22static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
23static constexpr double kKp[7] = { 100, 200, 100, 200, 100, 200, 100 };
24static constexpr double kKd[7] = { 10, 20, 10, 20, 10, 20, 10 };
25
26static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path(); }
27
28class MjcfTrqCtrlTest : public testing::Test
29{
30 protected:
31 fs::path root_;
32 mjModel *model_ = nullptr;
33 mjData *data_ = nullptr;
34
36 unsigned n_ = 0;
37 std::unique_ptr<KDL::ChainFkSolverPos_recursive> fk_;
38 std::unique_ptr<KDL::ChainDynParam> dyn_;
39 KDL::JntArray q_home_;
40
41 void SetUp() override
42 {
43 root_ = repo_root();
44 if (!fs::exists(root_ / "third_party/menagerie")) {
45 GTEST_SKIP() << "third_party/menagerie/ not found";
46 return;
47 }
48
49 const std::string arm_mjcf =
50 (root_ / "third_party/menagerie/kinova_gen3/gen3.xml").string();
51 const std::string grp_mjcf =
52 (root_ / "third_party/menagerie/robotiq_2f85/2f85.xml").string();
53
55 gs.mjcf_path = grp_mjcf.c_str();
56 gs.attach_to = "bracelet_link";
57 gs.prefix = "g_";
58 gs.pos[2] = -0.061525;
59 gs.euler[0] = 180.0;
60
62 rs.path = arm_mjcf.c_str();
63 rs.attachments.push_back(gs);
64
66 sc.robots.push_back(rs);
67
68 ASSERT_TRUE(mj_kdl::build_scene(&model_, &data_, &sc));
69 ASSERT_TRUE(
71 &s_, model_, data_, "base_link", "bracelet_link", "", "g_base"
72 )
73 );
74
75 n_ = s_.chain.getNrOfJoints();
76 fk_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(s_.chain);
77 dyn_ = std::make_unique<KDL::ChainDynParam>(s_.chain, KDL::Vector(0, 0, -9.81));
78
79 q_home_.resize(n_);
80 for (unsigned i = 0; i < n_; ++i) q_home_(i) = kHomePose[i];
82 mj_forward(model_, data_);
83 }
84
85 void TearDown() override
86 {
87 if (model_) {
90 }
91 }
92};
93
94TEST_F(MjcfTrqCtrlTest, GravityAccuracy)
95{
96 // At q=0 the arm is upright. KDL now includes gripper inertia via tool_body.
97 KDL::JntArray q_zero(n_);
98 mj_kdl::set_joint_pos(&s_, q_zero);
99 mj_forward(model_, data_);
100
101 KDL::JntArray g(n_);
102 ASSERT_GE(dyn_->JntToGravity(q_zero, g), 0);
103
104 double max_err = 0.0;
105 for (unsigned i = 0; i < n_; ++i)
106 max_err = std::max(max_err, std::abs(g(i) - data_->qfrc_bias[s_.kdl_to_mj_dof[i]]));
107 TEST_INFO(
108 "MJCF+gripper max|KDL - MuJoCo| gravity at q=0: " << std::fixed << std::setprecision(6)
109 << max_err << " Nm"
110 );
111 EXPECT_LE(max_err, 5e-2);
112}
113
114TEST_F(MjcfTrqCtrlTest, ImpedanceDrift)
115{
116 KDL::Frame ee_init;
117 fk_->JntToCart(q_home_, ee_init);
118
119 s_.ctrl_mode = mj_kdl::CtrlMode::TORQUE;
120
121 KDL::JntArray q(n_), g(n_);
122 for (int i = 0; i < 500; ++i) {
123 mj_kdl::update(&s_);
124 for (unsigned j = 0; j < n_; ++j) q(j) = s_.jnt_pos_msr[j];
125 dyn_->JntToGravity(q, g);
126 for (unsigned j = 0; j < n_; ++j) {
127 s_.jnt_trq_cmd[j] =
128 kKp[j] * (kHomePose[j] - s_.jnt_pos_msr[j]) - kKd[j] * s_.jnt_vel_msr[j] + g(j);
129 }
130 mj_kdl::step(&s_);
131 }
132
133 KDL::JntArray q_end(n_);
134 for (unsigned j = 0; j < n_; ++j) q_end(j) = s_.jnt_pos_msr[j];
135 KDL::Frame ee_end;
136 fk_->JntToCart(q_end, ee_end);
137 double drift = (ee_init.p - ee_end.p).Norm();
138 TEST_INFO(
139 "MJCF+gripper impedance drift after 500 steps: " << std::fixed << std::setprecision(3)
140 << drift * 1000.0 << " mm"
141 );
142 EXPECT_LE(drift, 0.005);
143}
144
145int main(int argc, char *argv[])
146{
147 testing::InitGoogleTest(&argc, argv);
148 return RUN_ALL_TESTS();
149}
void SetUp() override
std::unique_ptr< KDL::ChainDynParam > dyn_
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_
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< AttachmentSpec > attachments
std::vector< RobotSpec > robots
int main(int argc, char *argv[])
TEST_F(MjcfTrqCtrlTest, GravityAccuracy)
#define TEST_INFO(msg)