test_kinematics_as_plugin.cpp
Go to the documentation of this file.
1  /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sachin Chitta */
36 
37 #include <ros/ros.h>
38 #include <gtest/gtest.h>
40 
41 // MoveIt!
46 #include <urdf/model.h>
47 #include <srdfdom/model.h>
48 
49 #define IK_NEAR 1e-4
50 #define IK_NEAR_TRANSLATE 1e-5
51 
52 class MyTest
53 {
54  public:
55  bool initialize()
56  {
57  double search_discretization;
58  ros::NodeHandle nh("~");
59  kinematics_loader_.reset(new pluginlib::ClassLoader<kinematics::KinematicsBase>("moveit_core", "kinematics::KinematicsBase"));
60  std::string plugin_name;
61  if (!nh.getParam("plugin_name", plugin_name))
62  {
63  ROS_ERROR("No plugin name found on parameter server");
64  EXPECT_TRUE(0);
65  return false;
66  }
67  ROS_INFO("Plugin name: %s",plugin_name.c_str());
68  try
69  {
70  kinematics_solver_ = kinematics_loader_->createInstance(plugin_name);
71  }
72  catch(pluginlib::PluginlibException& ex)//handle the class failing to load
73  {
74  ROS_ERROR("The plugin failed to load. Error: %s", ex.what());
75  EXPECT_TRUE(0);
76  return false;
77  }
78  std::string root_name, tip_name;
79  ros::WallTime start_time = ros::WallTime::now();
80  bool done = true;
81  while((ros::WallTime::now()-start_time).toSec() <= 5.0)
82  {
83  if (!nh.getParam("root_name", root_name))
84  {
85  ROS_ERROR("No root name found on parameter server");
86  done = false;
87  EXPECT_TRUE(0);
88  continue;
89  }
90  if (!nh.getParam("tip_name", tip_name))
91  {
92  ROS_ERROR("No tip name found on parameter server");
93  done = false;
94  EXPECT_TRUE(0);
95  continue;
96  }
97  if (!nh.getParam("search_discretization", search_discretization))
98  {
99  ROS_ERROR("No search discretization found on parameter server");
100  done = false;
101  EXPECT_TRUE(0);
102  continue;
103  }
104  done = true;
105  }
106 
107  if(!done)
108  return false;
109 
110  if(kinematics_solver_->initialize("robot_description","right_arm",root_name,tip_name,search_discretization))
111  return true;
112  else
113  {
114  EXPECT_TRUE(0);
115  return false;
116  }
117 
118  };
119 
120  void joint_state_callback(const geometry_msgs::Pose &ik_pose,
121  const std::vector<double> &joint_state,
122  moveit_msgs::MoveItErrorCodes &error_code)
123  {
124  std::vector<std::string> link_names;
125  link_names.push_back("r_elbow_flex_link");
126  std::vector<geometry_msgs::Pose> solutions;
127  solutions.resize(1);
128  if(!kinematics_solver_->getPositionFK(link_names,joint_state,solutions))
129  error_code.val = error_code.PLANNING_FAILED;
130  if(solutions[0].position.z > 0.0)
131  error_code.val = error_code.SUCCESS;
132  else
133  error_code.val = error_code.PLANNING_FAILED;
134  };
135 
137  std::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase> > kinematics_loader_;
138 };
139 
141 
142 TEST(ArmIKPlugin, initialize)
143 {
144  ASSERT_TRUE(my_test.initialize());
145  // Test getting chain information
146  std::string root_name = my_test.kinematics_solver_->getBaseFrame();
147  EXPECT_TRUE(root_name == std::string("torso_lift_link"));
148  std::string tool_name = my_test.kinematics_solver_->getTipFrame();
149  EXPECT_TRUE(tool_name == std::string("r_wrist_roll_link"));
150  std::vector<std::string> joint_names = my_test.kinematics_solver_->getJointNames();
151  EXPECT_EQ((int)joint_names.size(), 7);
152 
153  EXPECT_EQ(joint_names[0], "r_shoulder_pan_joint");
154  EXPECT_EQ(joint_names[1], "r_shoulder_lift_joint");
155  EXPECT_EQ(joint_names[2], "r_upper_arm_roll_joint");
156  EXPECT_EQ(joint_names[3], "r_elbow_flex_joint");
157  EXPECT_EQ(joint_names[4], "r_forearm_roll_joint");
158  EXPECT_EQ(joint_names[5], "r_wrist_flex_joint");
159  EXPECT_EQ(joint_names[6], "r_wrist_roll_joint");
160 }
161 
162 TEST(ArmIKPlugin, getFK)
163 {
164  rdf_loader::RDFLoader rdf_loader_;
165  robot_model::RobotModelPtr kinematic_model;
166  const srdf::ModelSharedPtr& srdf = rdf_loader_.getSRDF();
167  const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader_.getURDF();
168  kinematic_model.reset(new robot_model::RobotModel(urdf_model, srdf));
169  robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver_->getGroupName());
170 
171  std::vector<double> seed, fk_values, solution;
172  moveit_msgs::MoveItErrorCodes error_code;
173  solution.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
174 
175  std::vector<std::string> fk_names;
176  fk_names.push_back(my_test.kinematics_solver_->getTipFrame());
177 
178  robot_state::RobotState kinematic_state(kinematic_model);
179 
180  ros::NodeHandle nh("~");
181  int number_fk_tests;
182  nh.param("number_fk_tests", number_fk_tests, 100);
183 
184  for(unsigned int i=0; i < (unsigned int) number_fk_tests; ++i)
185  {
186  seed.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
187  fk_values.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
188 
189  kinematic_state.setToRandomPositions(joint_model_group);
190  kinematic_state.copyJointGroupPositions(joint_model_group, fk_values);
191 
192  std::vector<geometry_msgs::Pose> poses;
193  poses.resize(1);
194  bool result_fk = my_test.kinematics_solver_->getPositionFK(fk_names, fk_values, poses);
195  ASSERT_TRUE(result_fk);
196  }
197 }
198 
199 TEST(ArmIKPlugin, searchIK)
200 {
201  rdf_loader::RDFLoader rdf_loader_;
202  robot_model::RobotModelPtr kinematic_model;
203  const srdf::ModelSharedPtr& srdf_model = rdf_loader_.getSRDF();
204  const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader_.getURDF();
205  kinematic_model.reset(new robot_model::RobotModel(urdf_model, srdf_model));
206  robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver_->getGroupName());
207 
208  //Test inverse kinematics
209  std::vector<double> seed, fk_values, solution;
210  double timeout = 5.0;
211  moveit_msgs::MoveItErrorCodes error_code;
212  solution.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
213 
214  std::vector<std::string> fk_names;
215  fk_names.push_back(my_test.kinematics_solver_->getTipFrame());
216 
217  robot_state::RobotState kinematic_state(kinematic_model);
218  // robot_state::JointStateGroup* joint_state_group = kinematic_state.getJointStateGroup(my_test.kinematics_solver_->getGroupName());
219 
220  ros::NodeHandle nh("~");
221  int number_ik_tests;
222  nh.param("number_ik_tests", number_ik_tests, 10);
223  unsigned int success = 0;
224 
225  ros::WallTime start_time = ros::WallTime::now();
226  for(unsigned int i=0; i < (unsigned int) number_ik_tests; ++i)
227  {
228  seed.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
229  fk_values.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
230 
231  kinematic_state.setToRandomPositions(joint_model_group);
232  kinematic_state.copyJointGroupPositions(joint_model_group, fk_values);
233 
234  std::vector<geometry_msgs::Pose> poses;
235  poses.resize(1);
236  bool result_fk = my_test.kinematics_solver_->getPositionFK(fk_names, fk_values, poses);
237  ASSERT_TRUE(result_fk);
238 
239  bool result = my_test.kinematics_solver_->searchPositionIK(poses[0], seed, timeout, solution, error_code);
240  ROS_DEBUG("Pose: %f %f %f",poses[0].position.x, poses[0].position.y, poses[0].position.z);
241  ROS_DEBUG("Orient: %f %f %f %f",poses[0].orientation.x, poses[0].orientation.y, poses[0].orientation.z, poses[0].orientation.w);
242  if(result)
243  {
244  success++;
245  result = my_test.kinematics_solver_->getPositionIK(poses[0], solution, solution, error_code);
246  EXPECT_TRUE(result);
247  }
248 
249  std::vector<geometry_msgs::Pose> new_poses;
250  new_poses.resize(1);
251  result_fk = my_test.kinematics_solver_->getPositionFK(fk_names, solution, new_poses);
252 
253  EXPECT_NEAR(poses[0].position.x, new_poses[0].position.x, IK_NEAR);
254  EXPECT_NEAR(poses[0].position.y, new_poses[0].position.y, IK_NEAR);
255  EXPECT_NEAR(poses[0].position.z, new_poses[0].position.z, IK_NEAR);
256 
257  EXPECT_NEAR(poses[0].orientation.x, new_poses[0].orientation.x, IK_NEAR);
258  EXPECT_NEAR(poses[0].orientation.y, new_poses[0].orientation.y, IK_NEAR);
259  EXPECT_NEAR(poses[0].orientation.z, new_poses[0].orientation.z, IK_NEAR);
260  EXPECT_NEAR(poses[0].orientation.w, new_poses[0].orientation.w, IK_NEAR);
261  }
262  ROS_INFO("Success Rate: %f",(double)success/number_ik_tests);
263  bool success_count = (success > 0.99 * number_ik_tests);
264  EXPECT_TRUE(success_count);
265  ROS_INFO("Elapsed time: %f", (ros::WallTime::now()-start_time).toSec());
266 }
267 
268 TEST(ArmIKPlugin, searchIKWithCallbacks)
269 {
270  rdf_loader::RDFLoader rdf_loader_;
271  robot_model::RobotModelPtr kinematic_model;
272  const srdf::ModelSharedPtr& srdf = rdf_loader_.getSRDF();
273  const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader_.getURDF();
274  kinematic_model.reset(new robot_model::RobotModel(urdf_model, srdf));
275  robot_model::JointModelGroup* joint_model_group = kinematic_model->getJointModelGroup(my_test.kinematics_solver_->getGroupName());
276 
277  //Test inverse kinematics
278  std::vector<double> seed,fk_values,solution;
279  double timeout = 5.0;
280  moveit_msgs::MoveItErrorCodes error_code;
281  solution.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
282 
283  std::vector<std::string> fk_names;
284  fk_names.push_back(my_test.kinematics_solver_->getTipFrame());
285 
286  robot_state::RobotState kinematic_state(kinematic_model);
287  // robot_state::JointStateGroup* joint_state_group = kinematic_state.getJointStateGroup(my_test.kinematics_solver_->getGroupName());
288 
289  ros::NodeHandle nh("~");
290  int number_ik_tests;
291  nh.param("number_ik_tests_with_callbacks", number_ik_tests, 10);
292  unsigned int success = 0;
293  unsigned int num_actual_tests = 0;
294 
295  for(unsigned int i=0; i < (unsigned int) number_ik_tests; ++i)
296  {
297  seed.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
298  fk_values.resize(my_test.kinematics_solver_->getJointNames().size(), 0.0);
299 
300  kinematic_state.setToRandomPositions(joint_model_group);
301  kinematic_state.copyJointGroupPositions(joint_model_group, fk_values);
302 
303  std::vector<geometry_msgs::Pose> poses;
304  poses.resize(1);
305  bool result_fk = my_test.kinematics_solver_->getPositionFK(fk_names, fk_values, poses);
306  ASSERT_TRUE(result_fk);
307  if(poses[0].position.z < 0.0)
308  continue;
309 
310  num_actual_tests++;
311  bool result = my_test.kinematics_solver_->searchPositionIK(poses[0], seed, timeout, solution,
312  boost::bind(&MyTest::joint_state_callback, &my_test, _1, _2, _3), error_code);
313 
314  if(result)
315  {
316  success++;
317  std::vector<geometry_msgs::Pose> new_poses;
318  new_poses.resize(1);
319  result_fk = my_test.kinematics_solver_->getPositionFK(fk_names, solution, new_poses);
320 
321  EXPECT_NEAR(poses[0].position.x, new_poses[0].position.x, IK_NEAR);
322  EXPECT_NEAR(poses[0].position.y, new_poses[0].position.y, IK_NEAR);
323  EXPECT_NEAR(poses[0].position.z, new_poses[0].position.z, IK_NEAR);
324 
325  EXPECT_NEAR(poses[0].orientation.x, new_poses[0].orientation.x, IK_NEAR);
326  EXPECT_NEAR(poses[0].orientation.y, new_poses[0].orientation.y, IK_NEAR);
327  EXPECT_NEAR(poses[0].orientation.z, new_poses[0].orientation.z, IK_NEAR);
328  EXPECT_NEAR(poses[0].orientation.w, new_poses[0].orientation.w, IK_NEAR);
329  }
330 
331  if(!ros::ok())
332  break;
333  }
334  ROS_INFO("Success with callbacks (%%): %f",(double)success/num_actual_tests*100.0);
335 }
336 
337 
338 int main(int argc, char **argv)
339 {
340  testing::InitGoogleTest(&argc, argv);
341  ros::init (argc, argv, "right_arm_kinematics");
342  return RUN_ALL_TESTS();
343 }
std::shared_ptr< pluginlib::ClassLoader< kinematics::KinematicsBase > > kinematics_loader_
const srdf::ModelSharedPtr & getSRDF() const
boost::shared_ptr< kinematics::KinematicsBase > kinematics_solver_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define EXPECT_NEAR(a, b, prec)
#define IK_NEAR
void joint_state_callback(const geometry_msgs::Pose &ik_pose, const std::vector< double > &joint_state, moveit_msgs::MoveItErrorCodes &error_code)
#define EXPECT_EQ(a, b)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TEST(ArmIKPlugin, initialize)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
static WallTime now()
bool getParam(const std::string &key, std::string &s) const
#define EXPECT_TRUE(args)
#define ROS_ERROR(...)
const urdf::ModelInterfaceSharedPtr & getURDF() const
#define ROS_DEBUG(...)


pr2_moveit_tests
Author(s): Sachin Chitta
autogenerated on Sun Nov 17 2019 03:24:53