mj-kdl-wrapper  0.1.0
MuJoCo + KDL bridge for robot kinematics and dynamics
Loading...
Searching...
No Matches
test_table_scene.cpp
Go to the documentation of this file.
1/* test_table_scene.cpp
2 * Load a robot arm on a table with pickable objects (cubes and spheres).
3 * Runs KDL gravity compensation so the arm holds position.
4 * Also tests runtime scene_add_object / scene_remove_object.
5 * Self-skips when third_party/menagerie is absent. */
6
7#include <gtest/gtest.h>
8
10#include "test_utils.hpp"
11
12#include <kdl/chainfksolverpos_recursive.hpp>
13#include <kdl/chaindynparam.hpp>
14
15#include <iostream>
16#include <iomanip>
17#include <memory>
18#include <string>
19#include <filesystem>
20
21static constexpr double kHomePose[7] = { 0.0, 0.2618, 3.1416, -2.2689, 0.0, 0.9599, 1.5708 };
22
23namespace fs = std::filesystem;
24static fs::path repo_root() { return fs::path(__FILE__).parent_path().parent_path(); }
25
26static mj_kdl::SceneObject make_box(
27 const char *name,
28 double x,
29 double y,
30 double hx,
31 double hy,
32 double hz,
33 float r,
34 float g,
35 float b,
36 double surface_z
37)
38{
40 o.name = name;
42 o.size[0] = hx;
43 o.size[1] = hy;
44 o.size[2] = hz;
45 o.pos[0] = x;
46 o.pos[1] = y;
47 o.pos[2] = surface_z + hz;
48 o.rgba[0] = r;
49 o.rgba[1] = g;
50 o.rgba[2] = b;
51 o.rgba[3] = 1.0f;
52 return o;
53}
54
55static mj_kdl::SceneObject make_sphere(
56 const char *name,
57 double x,
58 double y,
59 double radius,
60 float r,
61 float g,
62 float b,
63 double surface_z
64)
65{
67 o.name = name;
69 o.size[0] = radius;
70 o.pos[0] = x;
71 o.pos[1] = y;
72 o.pos[2] = surface_z + radius;
73 o.rgba[0] = r;
74 o.rgba[1] = g;
75 o.rgba[2] = b;
76 o.rgba[3] = 1.0f;
77 return o;
78}
79
80class TableSceneTest : public testing::Test
81{
82 protected:
83 std::string mjcf_;
85 mjModel *model_ = nullptr;
86 mjData *data_ = nullptr;
88 bool s_cleaned_ = false;
89
90 std::unique_ptr<KDL::ChainFkSolverPos_recursive> fk_;
91 std::unique_ptr<KDL::ChainDynParam> dyn_;
92
93 unsigned n_ = 0;
94 KDL::JntArray q_home_;
95
96 void SetUp() override
97 {
98 fs::path root = repo_root();
99 if (!fs::exists(root / "third_party/menagerie")) {
100 GTEST_SKIP() << "third_party/menagerie/ not found";
101 return;
102 }
103 mjcf_ = (root / "third_party/menagerie/kinova_gen3/gen3.xml").string();
104
105 // Table setup: surface at z = 0.7 m, robot mounted at table centre.
106 mj_kdl::TableSpec table;
107 table.enabled = true;
108 table.pos[0] = 0.0;
109 table.pos[1] = 0.0;
110 table.pos[2] = 0.7; // surface height
111 table.top_size[0] = 0.8; // half-extent x
112 table.top_size[1] = 0.6; // half-extent y
113 table.thickness = 0.04;
114 table.leg_radius = 0.03;
115
116 double surface_z = table.pos[2];
117
118 std::vector<mj_kdl::SceneObject> objects;
119 objects.push_back(
120 make_box("red_cube", 0.35, 0.10, 0.03, 0.03, 0.03, 1.0f, 0.2f, 0.2f, surface_z)
121 );
122 objects.push_back(
123 make_box("green_cube", 0.35, -0.10, 0.03, 0.03, 0.03, 0.2f, 1.0f, 0.2f, surface_z)
124 );
125 objects.push_back(
126 make_box("blue_cube", 0.35, 0.30, 0.04, 0.04, 0.04, 0.2f, 0.2f, 1.0f, surface_z)
127 );
128 objects.push_back(
129 make_sphere("orange_sphere", -0.20, 0.20, 0.035, 1.0f, 0.55f, 0.0f, surface_z)
130 );
131 objects.push_back(
132 make_sphere("purple_sphere", -0.20, -0.20, 0.025, 0.7f, 0.0f, 0.9f, surface_z)
133 );
134
135 spec_.table = table;
136 spec_.objects = objects;
137 spec_.add_floor = true;
138 spec_.gravity_z = -9.81;
139
140 mj_kdl::RobotSpec robot;
141 robot.path = mjcf_.c_str();
142 robot.prefix = "";
143 robot.pos[0] = 0.0;
144 robot.pos[1] = 0.0;
145 robot.pos[2] = surface_z;
146 spec_.robots.push_back(robot);
147
148 ASSERT_TRUE(mj_kdl::build_scene(&model_, &data_, &spec_));
149 TEST_INFO(model_->nbody << " bodies, " << model_->nq << " DOFs");
150
151 ASSERT_TRUE(mj_kdl::init_robot_from_mjcf(&s_, model_, data_, "base_link", "bracelet_link"));
152 TEST_INFO(s_.n_joints << " joints");
153
154 n_ = static_cast<unsigned>(s_.n_joints);
155
156 fk_ = std::make_unique<KDL::ChainFkSolverPos_recursive>(s_.chain);
157 dyn_ = std::make_unique<KDL::ChainDynParam>(s_.chain, KDL::Vector(0, 0, spec_.gravity_z));
158
159 q_home_.resize(n_);
160 for (unsigned i = 0; i < n_; ++i) q_home_(i) = kHomePose[i];
162 mj_forward(model_, data_);
163 }
164
165 void TearDown() override
166 {
169 }
170};
171
172TEST_F(TableSceneTest, GravityCompDrift)
173{
174 KDL::Frame ee_init;
175 fk_->JntToCart(q_home_, ee_init);
176
177 s_.ctrl_mode = mj_kdl::CtrlMode::TORQUE;
178 KDL::JntArray q(n_), g(n_);
179 // Prime jnt_trq_cmd so the first update() applies compensation immediately.
180 dyn_->JntToGravity(q_home_, g);
181 for (unsigned j = 0; j < n_; ++j) s_.jnt_trq_cmd[j] = g(j);
182 for (int i = 0; i < 500; ++i) {
183 mj_kdl::update(&s_);
184 for (unsigned j = 0; j < n_; ++j) q(j) = s_.jnt_pos_msr[j];
185 dyn_->JntToGravity(q, g);
186 for (unsigned j = 0; j < n_; ++j) s_.jnt_trq_cmd[j] = g(j);
187 mj_kdl::step(&s_);
188 }
189
190 KDL::JntArray q_end(n_);
191 KDL::Frame ee_end;
192 for (unsigned j = 0; j < n_; ++j) q_end(j) = s_.jnt_pos_msr[j];
193 fk_->JntToCart(q_end, ee_end);
194 double drift = (ee_init.p - ee_end.p).Norm();
195
196 TEST_INFO(
197 "EE drift after 500 steps: " << std::fixed << std::setprecision(3) << drift * 1000.0 << " mm"
198 );
199
200 ASSERT_LE(drift, 0.001) << "drift " << drift * 1000.0 << " mm exceeds 1 mm threshold";
201}
202
203TEST_F(TableSceneTest, AddRemoveObject)
204{
205 int nbody_before = model_->nbody;
206
207 mj_kdl::cleanup(&s_);
208 s_cleaned_ = true;
209
210 double surface_z = spec_.table.pos[2];
211 mj_kdl::SceneObject extra =
212 make_box("yellow_cube", 0.0, 0.4, 0.03, 0.03, 0.03, 1.0f, 1.0f, 0.0f, surface_z);
213
214 ASSERT_TRUE(mj_kdl::scene_add_object(&model_, &data_, &spec_, extra))
215 << "scene_add_object() returned false";
216 TEST_INFO("bodies: " << nbody_before << " -> " << model_->nbody << " (after add)");
217
218 ASSERT_TRUE(mj_kdl::scene_remove_object(&model_, &data_, &spec_, "yellow_cube"))
219 << "scene_remove_object() returned false";
220 TEST_INFO("bodies: " << model_->nbody << " (after remove)");
221}
222
223int main(int argc, char *argv[])
224{
225 testing::InitGoogleTest(&argc, argv);
226 return RUN_ALL_TESTS();
227}
KDL::JntArray q_home_
void SetUp() override
void TearDown() override
std::unique_ptr< KDL::ChainDynParam > dyn_
mj_kdl::SceneSpec spec_
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_
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)
bool scene_add_object(mjModel **model, mjData **data, SceneSpec *spec, const SceneObject &obj)
bool scene_remove_object(mjModel **model, mjData **data, SceneSpec *spec, const std::string &name)
void destroy_scene(mjModel *model, mjData *data)
std::vector< RobotSpec > robots
std::vector< SceneObject > objects
int main(int argc, char *argv[])
TEST_F(TableSceneTest, GravityCompDrift)
#define TEST_INFO(msg)