7#include <gtest/gtest.h>
9#include <kdl/chaindynparam.hpp>
10#include <kdl/chainfksolverpos_recursive.hpp>
20namespace fs = std::filesystem;
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 };
26static fs::path repo_root() {
return fs::path(__FILE__).parent_path().parent_path(); }
37 std::unique_ptr<KDL::ChainFkSolverPos_recursive>
fk_;
38 std::unique_ptr<KDL::ChainDynParam>
dyn_;
44 if (!fs::exists(
root_ /
"third_party/menagerie")) {
45 GTEST_SKIP() <<
"third_party/menagerie/ not found";
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();
58 gs.
pos[2] = -0.061525;
62 rs.
path = arm_mjcf.c_str();
71 &
s_,
model_,
data_,
"base_link",
"bracelet_link",
"",
"g_base"
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));
80 for (
unsigned i = 0; i <
n_; ++i)
q_home_(i) = kHomePose[i];
97 KDL::JntArray q_zero(n_);
99 mj_forward(model_, data_);
102 ASSERT_GE(dyn_->JntToGravity(q_zero, g), 0);
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]]));
108 "MJCF+gripper max|KDL - MuJoCo| gravity at q=0: " << std::fixed << std::setprecision(6)
111 EXPECT_LE(max_err, 5e-2);
117 fk_->JntToCart(q_home_, ee_init);
121 KDL::JntArray q(n_), g(n_);
122 for (
int i = 0; i < 500; ++i) {
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) {
128 kKp[j] * (kHomePose[j] - s_.jnt_pos_msr[j]) - kKd[j] * s_.jnt_vel_msr[j] + g(j);
133 KDL::JntArray q_end(n_);
134 for (
unsigned j = 0; j < n_; ++j) q_end(j) = s_.jnt_pos_msr[j];
136 fk_->JntToCart(q_end, ee_end);
137 double drift = (ee_init.p - ee_end.p).Norm();
139 "MJCF+gripper impedance drift after 500 steps: " << std::fixed << std::setprecision(3)
140 << drift * 1000.0 <<
" mm"
142 EXPECT_LE(drift, 0.005);
145int main(
int argc,
char *argv[])
147 testing::InitGoogleTest(&argc, argv);
148 return RUN_ALL_TESTS();
std::unique_ptr< KDL::ChainDynParam > dyn_
std::unique_ptr< KDL::ChainFkSolverPos_recursive > fk_
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)
std::vector< AttachmentSpec > attachments
std::vector< RobotSpec > robots
int main(int argc, char *argv[])
TEST_F(MjcfTrqCtrlTest, GravityAccuracy)