test_kuka_specific.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <vector>
3 #include <string>
4 
5 #include <ros/ros.h>
8 
9 #include "test_utils.h"
10 
11 class TestKukaSpecific : public testing::Test
12 {
13 protected:
14  void SetUp() override
15  {
16  plugin_.initialize("robot_description", "manipulator", "base_link", "tool0", 0.1);
17  };
18  void TearDown() override{};
19 
20 protected:
22 };
23 
31 TEST_F(TestKukaSpecific, positionFKAllZero)
32 {
33  using Eigen::AngleAxisd;
34  using Eigen::Translation3d;
35  using Eigen::Vector3d;
36 
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;
40 
41  plugin_.getPositionFK(plugin_.getLinkNames(), joint_angles, poses);
42 
43  Eigen::Affine3d pose_actual, pose_desired;
44  tf::poseMsgToEigen(poses[0], pose_actual);
45 
46 
47  pose_desired = Translation3d(0.785, 0, 0.435) * AngleAxisd(M_PI_2, Vector3d::UnitY());
48 
49  moveit_opw_kinematics_plugin::testing::comparePoses(pose_actual, pose_desired);
50 }
51 
59 TEST_F(TestKukaSpecific, positionFKCheckSigns)
60 {
61  using Eigen::AngleAxisd;
62  using Eigen::Translation3d;
63  using Eigen::Vector3d;
64 
65  const double J1 = M_PI_2, J4 = 0.3, J6 = 0.2;
66 
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;
70 
71  plugin_.getPositionFK(plugin_.getLinkNames(), joint_angles, poses);
72 
73  Eigen::Affine3d pose_actual, pose_desired;
74  tf::poseMsgToEigen(poses[0], pose_actual);
75 
76 
77  // rotation for the joint offset of joint 2
78  pose_desired = Translation3d(0, 0, 0) * AngleAxisd(M_PI_2, Vector3d::UnitY());
79 
80  // rotate around GLOBAL z to add rotation caused by joint 1
81  pose_desired = AngleAxisd(-J1, Vector3d::UnitZ()) * pose_desired;
82 
83  // rotate two times around LOCAL z-axis for joints J4 and J6
84  pose_desired = pose_desired * AngleAxisd(-J4, Vector3d::UnitZ()) * AngleAxisd(-J6, Vector3d::UnitZ());
85 
86  // put the frame at the expected position, non-zero y-value
87  // instead of x caused by the rotation of joint 1
88  pose_desired = Translation3d(0, -0.785, 0.435) * pose_desired;
89 
90  moveit_opw_kinematics_plugin::testing::comparePoses(pose_actual, pose_desired);
91 }
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
#define M_PI_2
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.
Definition: test_utils.h:20
moveit_opw_kinematics_plugin::MoveItOPWKinematicsPlugin plugin_
void TearDown() override
void SetUp() override


moveit_opw_kinematics_plugin
Author(s): Jeroen De Maeyer, Simon Schmeisser (isys vision)
autogenerated on Wed Jun 3 2020 03:17:14