test_plugin.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <ros/ros.h>
3 
9 
10 #include "test_utils.h"
11 
12 // Names to read values from the parameter server
13 const std::string GROUP_PARAM = "group";
14 const std::string TIP_LINK_PARAM = "tip_link";
15 const std::string ROOT_LINK_PARAM = "root_link";
16 
17 // Robot description almost always called "robot_description" and therefore hardcoded below
18 const std::string ROBOT_DESCRIPTION = "robot_description";
19 
26 class TestPlugin : public ::testing::Test
27 {
28 protected:
29  void SetUp() override
30  {
31  ros::NodeHandle nh;
34  {
35  // the last parameter specifies "search_discretization", which is not used by the opw plugin
37  }
38  else
39  {
40  ROS_ERROR_STREAM("Failed to load parameters necessary to load plugin.");
41  }
42  }
43  void TearDown() override
44  {
45  }
46 
48  std::string root_link_;
49  std::string tip_link_;
50  std::string group_name_;
51  std::string robot_description_name_;
52 };
53 
55 {
56  ASSERT_EQ(plugin_.getGroupName(), group_name_);
57 }
58 
59 TEST_F(TestPlugin, CompareIKAndFK)
60 {
61  std::vector<std::string> link_names;
62  const std::vector<double> joint_angles = { 0, 0.1, 0.2, 0.3, 0.4, 0.5 };
63  std::vector<geometry_msgs::Pose> poses_out;
64 
65  // find reachable pose
66  plugin_.getPositionFK(plugin_.getLinkNames(), joint_angles, poses_out);
67 
68  // calculate all ik solutions for this pose
69  const std::vector<geometry_msgs::Pose> poses_in = { poses_out[0] };
70  std::vector<std::vector<double> > solutions;
72  bool res = plugin_.getPositionIK(poses_in, joint_angles, solutions, result);
73  EXPECT_TRUE(res);
74 
75  // check if fk for all this solutions gives the same pose
76  Eigen::Affine3d actual, desired;
77  tf::poseMsgToEigen(poses_out[0], desired);
78  for (auto js : solutions)
79  {
80  plugin_.getPositionFK(plugin_.getLinkNames(), js, poses_out);
81  tf::poseMsgToEigen(poses_out[0], actual);
83  }
84 }
85 
86 int main(int argc, char** argv)
87 {
88  ros::init(argc, argv, "moveit_opw_kinematics_test_fanuc");
89  testing::InitGoogleTest(&argc, argv);
90  return RUN_ALL_TESTS();
91 }
int main(int argc, char **argv)
Definition: test_plugin.cpp:86
virtual const std::string & getGroupName() const
const std::string ROOT_LINK_PARAM
Definition: test_plugin.cpp:15
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)
void TearDown() override
Definition: test_plugin.cpp:43
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void SetUp() override
Definition: test_plugin.cpp:29
const std::string GROUP_PARAM
Definition: test_plugin.cpp:13
std::string tip_link_
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
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.
Definition: test_utils.h:20
const std::string ROBOT_DESCRIPTION
Definition: test_plugin.cpp:18
std::string robot_description_name_
moveit_opw_kinematics_plugin::MoveItOPWKinematicsPlugin plugin_
std::string root_link_
bool getParam(const std::string &key, std::string &s) const
std::string group_name_
#define ROS_ERROR_STREAM(args)
#define EXPECT_TRUE(args)
TEST_F(TestPlugin, InitOk)
Definition: test_plugin.cpp:54
const std::string TIP_LINK_PARAM
Definition: test_plugin.cpp:14


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