-
Notifications
You must be signed in to change notification settings - Fork 119
/
test_jacobian.cpp
143 lines (126 loc) · 5.02 KB
/
test_jacobian.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Sachin Chitta */
#include <ros/ros.h>
#include <moveit/rdf_loader/rdf_loader.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
// KDL
#include <kdl/jntarray.hpp>
#include <kdl_parser/kdl_parser.hpp>
#include <kdl/chainiksolverpos_nr_jl.hpp>
#include <kdl/chainiksolvervel_pinv.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/chainjnttojacsolver.hpp>
#include <gtest/gtest.h>
double gen_rand(double min, double max)
{
int rand_num = rand()%100+1;
double result = min + (double)((max-min)*rand_num)/101.0;
return result;
}
bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
{
if(fabs(v1-v2) > NEAR)
return true;
return false;
}
void testJacobian(std::string group_name, std::string base_link, std::string tip_link)
{
SCOPED_TRACE(group_name + ": " + base_link + " to " + tip_link);
srand ( time(NULL) ); // initialize random seed:
rdf_loader::RDFLoader model_loader("robot_description");
robot_model::RobotModelPtr kinematic_model;
kinematic_model.reset(new robot_model::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
robot_state::RobotStatePtr kinematic_state;
kinematic_state.reset(new robot_state::RobotState(kinematic_model));
kinematic_state->setToDefaultValues();
const moveit::core::JointModelGroup* joint_state_group = kinematic_state->getRobotModel()->getJointModelGroup(group_name);
std::string link_name = tip_link;
std::vector<double> joint_angles(7,0.0);
geometry_msgs::Point ref_position;
Eigen::MatrixXd jacobian;
Eigen::Vector3d point(0.0,0.0,0.0);
kinematic_state->setJointGroupPositions(joint_state_group, &joint_angles[0]);
ASSERT_TRUE(kinematic_state->getJacobian(joint_state_group, kinematic_state->getRobotModel()->getLinkModel(link_name),point,jacobian));
KDL::Tree tree;
if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
{
ROS_ERROR("Could not initialize tree object");
}
KDL::Chain kdl_chain;
std::string base_frame(base_link);
std::string tip_frame(tip_link);
if (!tree.getChain(base_frame, tip_frame, kdl_chain))
{
ROS_ERROR("Could not initialize chain object");
}
KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
KDL::Jacobian jacobian_kdl(7);
KDL::JntArray q_in(7);
EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
unsigned int NUM_TESTS = 10000;
for(unsigned int i=0; i < NUM_TESTS; i++)
{
for(int j=0; j < 7; j++)
{
q_in(j) = gen_rand(-M_PI,M_PI);
joint_angles[j] = q_in(j);
}
EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
kinematic_state->setJointGroupPositions(joint_state_group, &joint_angles[0]);
EXPECT_TRUE(kinematic_state->getJacobian(joint_state_group, kinematic_state->getRobotModel()->getLinkModel(link_name), point, jacobian));
for(unsigned int k=0; k < 6; k++)
{
for(unsigned int m=0; m < 7; m++)
{
EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
}
}
}
}
TEST(JacobianSolver, solver)
{
testJacobian("right_arm", "torso_lift_link", "r_wrist_roll_link");
}
TEST(JacobianSolver, solver2)
{
testJacobian("left_arm", "torso_lift_link", "l_wrist_roll_link");
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "test_jacobian_solver");
return RUN_ALL_TESTS();
}