1 #include <gtest/gtest.h> 16 plugin_.
initialize(
"robot_description",
"manipulator",
"base_link",
"tool0", 0.1);
33 using Eigen::AngleAxisd;
34 using Eigen::Translation3d;
35 using Eigen::Vector3d;
37 std::vector<std::string> link_names;
38 std::vector<double> joint_angles = { 0, 0, 0, 0, 0, 0 };
39 std::vector<geometry_msgs::Pose> poses;
43 Eigen::Affine3d pose_actual, pose_desired;
47 pose_desired = Translation3d(0.785, 0, 0.435) * AngleAxisd(
M_PI_2, Vector3d::UnitY());
61 using Eigen::AngleAxisd;
62 using Eigen::Translation3d;
63 using Eigen::Vector3d;
65 const double J1 =
M_PI_2, J4 = 0.3, J6 = 0.2;
67 std::vector<std::string> link_names;
68 std::vector<double> joint_angles = { J1, 0, 0, J4, 0, J6 };
69 std::vector<geometry_msgs::Pose> poses;
73 Eigen::Affine3d pose_actual, pose_desired;
78 pose_desired = Translation3d(0, 0, 0) * AngleAxisd(
M_PI_2, Vector3d::UnitY());
81 pose_desired = AngleAxisd(-J1, Vector3d::UnitZ()) * pose_desired;
84 pose_desired = pose_desired * AngleAxisd(-J4, Vector3d::UnitZ()) * AngleAxisd(-J6, Vector3d::UnitZ());
88 pose_desired = Translation3d(0, -0.785, 0.435) * pose_desired;
TEST_F(TestKukaSpecific, positionFKAllZero)
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_frame, double search_discretization) override
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
void comparePoses(const Transform< T > &Ta, const Transform< T > &Tb)
Compare every element of two eigen affine3 poses.
moveit_opw_kinematics_plugin::MoveItOPWKinematicsPlugin plugin_