13#include <gtest/gtest.h>
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;
25static constexpr double kSettleTime = 0.5;
26static constexpr double kErrTol = 0.05;
28namespace fs = std::filesystem;
29static fs::path repo_root() {
return fs::path(__FILE__).parent_path().parent_path(); }
43 if (!fs::exists(
root_ /
"third_party/menagerie")) {
44 GTEST_SKIP() <<
"third_party/menagerie/ not found";
48 std::string arm_mjcf = (
root_ /
"third_party/menagerie/kinova_gen3/gen3.xml").
string();
52 r.
path = arm_mjcf.c_str();
60 KDL::JntArray q_home(
n_);
61 for (
unsigned i = 0; i <
n_; ++i) q_home(i) = kHomePose[i];
81 const double t_start = data_->time;
82 const double t_end = t_start + kMotionDuration + kSettleTime;
84 while (data_->time < t_end) {
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]);
93 for (
unsigned i = 0; i < n_; ++i)
94 max_err = std::max(max_err, std::abs(kTargetPose[i] - s_.jnt_pos_msr[i]));
97 "MJCF position ctrl max joint error after "
98 << (kMotionDuration + kSettleTime) <<
" s: " << std::fixed << std::setprecision(4) << max_err
101 EXPECT_LE(max_err, kErrTol);
104int main(
int argc,
char *argv[])
106 testing::InitGoogleTest(&argc, argv);
107 return RUN_ALL_TESTS();
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< double > jnt_pos_cmd
std::vector< RobotSpec > robots
int main(int argc, char *argv[])
TEST_F(MjcfPosCtrlTest, TrajectoryTracking)