test_jacobian.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 
42 
43 // KDL
44 #include <kdl/jntarray.hpp>
46 #include <kdl/chainiksolverpos_nr_jl.hpp>
47 #include <kdl/chainiksolvervel_pinv.hpp>
48 #include <kdl/chainfksolverpos_recursive.hpp>
49 #include <kdl/chainjnttojacsolver.hpp>
50 
51 #include <gtest/gtest.h>
52 
53 double gen_rand(double min, double max)
54 {
55  int rand_num = rand()%100+1;
56  double result = min + (double)((max-min)*rand_num)/101.0;
57  return result;
58 }
59 
60 bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
61 {
62  if(fabs(v1-v2) > NEAR)
63  return true;
64  return false;
65 }
66 
67 void testJacobian(std::string group_name, std::string base_link, std::string tip_link)
68 {
69  SCOPED_TRACE(group_name + ": " + base_link + " to " + tip_link);
70 
71  srand ( time(NULL) ); // initialize random seed:
72  rdf_loader::RDFLoader model_loader("robot_description");
73  robot_model::RobotModelPtr kinematic_model;
74  kinematic_model.reset(new robot_model::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
75 
76  robot_state::RobotStatePtr kinematic_state;
77  kinematic_state.reset(new robot_state::RobotState(kinematic_model));
78  kinematic_state->setToDefaultValues();
79 
80  const moveit::core::JointModelGroup* joint_state_group = kinematic_state->getRobotModel()->getJointModelGroup(group_name);
81 
82  std::string link_name = tip_link;
83  std::vector<double> joint_angles(7,0.0);
84  geometry_msgs::Point ref_position;
85  Eigen::MatrixXd jacobian;
86  Eigen::Vector3d point(0.0,0.0,0.0);
87  kinematic_state->setJointGroupPositions(joint_state_group, &joint_angles[0]);
88  ASSERT_TRUE(kinematic_state->getJacobian(joint_state_group, kinematic_state->getRobotModel()->getLinkModel(link_name),point,jacobian));
89 
90  KDL::Tree tree;
91  if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
92  {
93  ROS_ERROR("Could not initialize tree object");
94  }
95  KDL::Chain kdl_chain;
96  std::string base_frame(base_link);
97  std::string tip_frame(tip_link);
98  if (!tree.getChain(base_frame, tip_frame, kdl_chain))
99  {
100  ROS_ERROR("Could not initialize chain object");
101  }
102  KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
103  KDL::Jacobian jacobian_kdl(7);
104  KDL::JntArray q_in(7);
105  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
106 
107  unsigned int NUM_TESTS = 10000;
108  for(unsigned int i=0; i < NUM_TESTS; i++)
109  {
110  for(int j=0; j < 7; j++)
111  {
112  q_in(j) = gen_rand(-M_PI,M_PI);
113  joint_angles[j] = q_in(j);
114  }
115  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
116  kinematic_state->setJointGroupPositions(joint_state_group, &joint_angles[0]);
117  EXPECT_TRUE(kinematic_state->getJacobian(joint_state_group, kinematic_state->getRobotModel()->getLinkModel(link_name), point, jacobian));
118  for(unsigned int k=0; k < 6; k++)
119  {
120  for(unsigned int m=0; m < 7; m++)
121  {
122  EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
123  }
124  }
125  }
126 }
127 
128 TEST(JacobianSolver, solver)
129 {
130  testJacobian("right_arm", "torso_lift_link", "r_wrist_roll_link");
131 }
132 
133 TEST(JacobianSolver, solver2)
134 {
135  testJacobian("left_arm", "torso_lift_link", "l_wrist_roll_link");
136 }
137 
138 int main(int argc, char **argv)
139 {
140  testing::InitGoogleTest(&argc, argv);
141  ros::init(argc, argv, "test_jacobian_solver");
142  return RUN_ALL_TESTS();
143 }
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
const srdf::ModelSharedPtr & getSRDF() const
const LinkModel * getLinkModel(const std::string &link) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define M_PI
#define EXPECT_FALSE(args)
int main(int argc, char **argv)
virtual int JntToJac(const JntArray &q_in, Jacobian &jac, int segmentNR=-1)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
double gen_rand(double min, double max)
#define EXPECT_TRUE(args)
#define ROS_ERROR(...)
bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
void testJacobian(std::string group_name, std::string base_link, std::string tip_link)
TEST(JacobianSolver, solver)
const urdf::ModelInterfaceSharedPtr & getURDF() const


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