51 builder.
addChain(
"a->b",
"continuous");
52 builder.
addChain(
"b->c",
"prismatic");
54 robot_model_ = builder.
build();
64 static std::size_t generateTestTraj(std::vector<std::shared_ptr<RobotState>>& traj,
65 const RobotModelConstPtr& robot_model_);
69 const RobotModelConstPtr& robot_model_)
78 for (std::size_t traj_ix = 0; traj_ix < 3; ++traj_ix)
80 traj.push_back(std::make_shared<RobotState>(*
robot_state));
91 traj.push_back(std::make_shared<RobotState>(*
robot_state));
96 traj.push_back(std::make_shared<RobotState>(*
robot_state));
101 traj.push_back(std::make_shared<RobotState>(*
robot_state));
104 traj.push_back(std::make_shared<RobotState>(*
robot_state));
111 std::vector<std::shared_ptr<RobotState>> traj;
114 const std::size_t expected_full_traj_len = 7;
117 std::size_t full_traj_len = generateTestTraj(traj, robot_model_);
120 EXPECT_EQ(full_traj_len, expected_full_traj_len);
125 const JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(
"group");
126 std::vector<std::shared_ptr<RobotState>> traj;
129 const std::size_t expected_revolute_jump_traj_len = 4;
130 const std::size_t expected_prismatic_jump_traj_len = 5;
133 std::size_t full_traj_len = generateTestTraj(traj, robot_model_);
134 const double expected_revolute_jump_fraction = (double)expected_revolute_jump_traj_len / (
double)full_traj_len;
135 const double expected_prismatic_jump_fraction = (double)expected_prismatic_jump_traj_len / (
double)full_traj_len;
142 EXPECT_EQ(expected_revolute_jump_traj_len, traj.size());
143 EXPECT_NEAR(expected_revolute_jump_fraction, fraction, 0.01);
146 generateTestTraj(traj, robot_model_);
148 EXPECT_EQ(expected_revolute_jump_traj_len, traj.size());
149 EXPECT_NEAR(expected_revolute_jump_fraction, fraction, 0.01);
152 generateTestTraj(traj, robot_model_);
154 EXPECT_EQ(expected_revolute_jump_traj_len, traj.size());
155 EXPECT_NEAR(expected_revolute_jump_fraction, fraction, 0.01);
158 generateTestTraj(traj, robot_model_);
160 EXPECT_EQ(expected_prismatic_jump_traj_len, traj.size());
161 EXPECT_NEAR(expected_prismatic_jump_fraction, fraction, 0.01);
164 generateTestTraj(traj, robot_model_);
172 const JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(
"group");
173 std::vector<std::shared_ptr<RobotState>> traj;
176 const std::size_t expected_relative_jump_traj_len = 4;
179 std::size_t full_traj_len = generateTestTraj(traj, robot_model_);
180 const double expected_relative_jump_fraction = (double)expected_relative_jump_traj_len / (
double)full_traj_len;
187 EXPECT_EQ(expected_relative_jump_traj_len, traj.size());
188 EXPECT_NEAR(expected_relative_jump_fraction, fraction, 0.01);
191 generateTestTraj(traj, robot_model_);
193 EXPECT_EQ(expected_relative_jump_traj_len, traj.size());
194 EXPECT_NEAR(expected_relative_jump_fraction, fraction, 0.01);
197 generateTestTraj(traj, robot_model_);
209 jmg_ = robot_model_->getJointModelGroup(
"panda_arm");
210 link_ = robot_model_->getLinkModel(
"panda_link8");
217 robot_model_.reset();
222 start_state_ = std::make_shared<RobotState>(robot_model_);
223 ASSERT_TRUE(start_state_->setToDefaultValues(jmg_,
"ready"));
224 start_pose_ = start_state_->getGlobalLinkTransform(link_);
236 bool global,
const Eigen::Isometry3d& offset = Eigen::Isometry3d::Identity())
252 std::vector<std::shared_ptr<RobotState>>
result_;
261 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, translation,
true), 0.2);
263 EXPECT_EIGEN_EQ(result_.front()->getGlobalLinkTransform(link_), start_pose_);
265 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).linear(), start_pose_.linear(), prec_);
267 start_pose_.translation() + translation, prec_);
272 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, translation,
false), 0.2);
274 EXPECT_EIGEN_EQ(result_.front()->getGlobalLinkTransform(link_), start_pose_);
276 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).linear(), start_pose_.linear(), prec_);
277 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).translation(), start_pose_ * translation, prec_);
282 Eigen::Isometry3d goal = start_pose_;
283 goal.translation().x() += 0.2;
285 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, goal,
true), 1.0);
287 EXPECT_EIGEN_EQ(result_.front()->getGlobalLinkTransform(link_), start_pose_);
289 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).linear(), start_pose_.linear(), prec_);
290 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).translation(), goal.translation(), prec_);
294 Eigen::Isometry3d offset(Eigen::Translation3d(0.2, 0, 0));
295 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, offset,
false), 1.0);
297 EXPECT_EIGEN_EQ(result_.front()->getGlobalLinkTransform(link_), start_pose_);
299 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).linear(), start_pose_.linear(), prec_);
300 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).translation(), start_pose_ * offset.translation(),
307 Eigen::Isometry3d rot(Eigen::AngleAxisd(
M_PI / 4, Eigen::Vector3d::UnitX()));
308 Eigen::Isometry3d goal = start_pose_ * rot;
310 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, rot,
false), 1.0);
312 EXPECT_EIGEN_EQ(result_.front()->getGlobalLinkTransform(link_), start_pose_);
314 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).translation(), start_pose_.translation(), prec_);
320 Eigen::Isometry3d rot(Eigen::AngleAxisd(
M_PI / 4, Eigen::Vector3d::UnitX()));
321 Eigen::Isometry3d goal = start_pose_ * rot;
323 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, goal,
true), 1.0);
325 EXPECT_EIGEN_NEAR(result_.front()->getGlobalLinkTransform(link_), start_pose_, prec_);
327 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_).translation(), start_pose_.translation(), prec_);
333 Eigen::Isometry3d offset = Eigen::Translation3d(0, 0, 0.2) * Eigen::AngleAxisd(-
M_PI / 4, Eigen::Vector3d::UnitZ());
335 Eigen::Isometry3d rot(Eigen::AngleAxisd(
M_PI / 4, Eigen::Vector3d::UnitX()));
336 Eigen::Isometry3d goal = start_pose_ * offset * rot;
338 ASSERT_DOUBLE_EQ(computeCartesianPath(result_, goal,
true, offset), 1.0);
340 EXPECT_EIGEN_NEAR(result_.front()->getGlobalLinkTransform(link_), start_pose_, prec_);
343 for (
const auto& waypoint : result_)
344 EXPECT_EIGEN_NEAR((waypoint->getGlobalLinkTransform(link_) * offset).translation(),
345 (start_pose_ * offset).translation(), prec_);
347 EXPECT_EIGEN_NEAR(result_.back()->getGlobalLinkTransform(link_) * offset, goal, prec_);
350 int main(
int argc,
char** argv)
352 testing::InitGoogleTest(&argc, argv);
353 ros::init(argc, argv,
"test_cartesian_interpolator");
354 return RUN_ALL_TESTS();