test_jacobian.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Sachin Chitta */
00036 
00037 #include <ros/ros.h>
00038 
00039 #include <moveit/rdf_loader/rdf_loader.h>
00040 #include <moveit/robot_model/robot_model.h>
00041 #include <moveit/robot_state/robot_state.h>
00042 
00043 // KDL
00044 #include <kdl/jntarray.hpp>
00045 #include <kdl_parser/kdl_parser.hpp>
00046 #include <kdl/chainiksolverpos_nr_jl.hpp>
00047 #include <kdl/chainiksolvervel_pinv.hpp>
00048 #include <kdl/chainfksolverpos_recursive.hpp>
00049 #include <kdl/chainjnttojacsolver.hpp>
00050 
00051 #include <gtest/gtest.h>
00052 
00053 double gen_rand(double min, double max)
00054 {
00055   int rand_num = rand()%100+1;
00056   double result = min + (double)((max-min)*rand_num)/101.0;
00057   return result;
00058 }
00059 
00060 bool NOT_NEAR(const double &v1, const double &v2, const double &NEAR)
00061 {
00062    if(fabs(v1-v2) > NEAR)
00063       return true;
00064    return false;
00065 }
00066 
00067 TEST(JacobianSolver, solver)
00068 {
00069  srand ( time(NULL) ); // initialize random seed:
00070  rdf_loader::RDFLoader model_loader("robot_description");
00071  robot_model::RobotModelPtr kinematic_model;
00072  kinematic_model.reset(new robot_model::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
00073 
00074  robot_state::RobotStatePtr kinematic_state;
00075  kinematic_state.reset(new robot_state::RobotState(kinematic_model));
00076  kinematic_state->setToDefaultValues();
00077 
00078  robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("right_arm");
00079 
00080  std::string link_name = "r_wrist_roll_link";
00081  std::vector<double> joint_angles(7,0.0);
00082  geometry_msgs::Point ref_position;
00083  Eigen::MatrixXd jacobian;
00084  Eigen::Vector3d point(0.0,0.0,0.0);
00085  joint_state_group->setVariableValues(joint_angles);
00086  ASSERT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00087 
00088  KDL::Tree tree;
00089  if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
00090  {
00091    ROS_ERROR("Could not initialize tree object");
00092  }
00093  KDL::Chain kdl_chain;
00094  std::string base_frame("torso_lift_link");
00095  std::string tip_frame("r_wrist_roll_link");
00096  if (!tree.getChain(base_frame, tip_frame, kdl_chain))
00097  {
00098    ROS_ERROR("Could not initialize chain object");
00099  }
00100  KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
00101  KDL::Jacobian jacobian_kdl(7);
00102  KDL::JntArray q_in(7);
00103  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00104 
00105  unsigned int NUM_TESTS = 1000000;
00106  for(unsigned int i=0; i < NUM_TESTS; i++)
00107  {
00108    for(int j=0; j < 7; j++)
00109    {
00110      q_in(j) = gen_rand(-M_PI,M_PI);
00111      joint_angles[j] = q_in(j);
00112    }
00113    EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00114    joint_state_group->setVariableValues(joint_angles);
00115    EXPECT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00116    for(unsigned int k=0; k < 6; k++)
00117    {
00118      for(unsigned int m=0; m < 7; m++)
00119      {
00120        EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
00121      }
00122    }
00123  }
00124 }
00125 
00126 TEST(JacobianSolver, solver2)
00127 {
00128  srand ( time(NULL) ); // initialize random seed:
00129  rdf_loader::RDFLoader model_loader("robot_description");
00130  robot_model::RobotModelPtr kinematic_model;
00131  kinematic_model.reset(new robot_model::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
00132 
00133  robot_state::RobotStatePtr kinematic_state;
00134  kinematic_state.reset(new robot_state::RobotState(kinematic_model));
00135  kinematic_state->setToDefaultValues();
00136 
00137  robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("left_arm");
00138 
00139  std::string link_name = "l_wrist_roll_link";
00140  std::vector<double> joint_angles(7,0.0);
00141  geometry_msgs::Point ref_position;
00142  Eigen::MatrixXd jacobian;
00143  Eigen::Vector3d point(0.0,0.0,0.0);
00144  joint_state_group->setVariableValues(joint_angles);
00145  ASSERT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00146 
00147  KDL::Tree tree;
00148  if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
00149  {
00150    ROS_ERROR("Could not initialize tree object");
00151  }
00152  KDL::Chain kdl_chain;
00153  std::string base_frame("torso_lift_link");
00154  std::string tip_frame("l_wrist_roll_link");
00155  if (!tree.getChain(base_frame, tip_frame, kdl_chain))
00156  {
00157    ROS_ERROR("Could not initialize chain object");
00158  }
00159  KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
00160  KDL::Jacobian jacobian_kdl(7);
00161  KDL::JntArray q_in(7);
00162  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00163 
00164  unsigned int NUM_TESTS = 1000000;
00165  for(unsigned int i=0; i < NUM_TESTS; i++)
00166  {
00167    for(int j=0; j < 7; j++)
00168    {
00169      q_in(j) = gen_rand(-M_PI,M_PI);
00170      joint_angles[j] = q_in(j);
00171    }
00172    EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00173    joint_state_group->setVariableValues(joint_angles);
00174    EXPECT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00175    for(unsigned int k=0; k < 6; k++)
00176    {
00177      for(unsigned int m=0; m < 7; m++)
00178      {
00179        EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
00180      }
00181    }
00182  }
00183 }
00184 
00185 int main(int argc, char **argv)
00186 {
00187   testing::InitGoogleTest(&argc, argv);
00188   ros::init(argc, argv, "test_jacobian_solver");
00189   return RUN_ALL_TESTS();
00190 }


pr2_moveit_tests
Author(s):
autogenerated on Mon Oct 6 2014 11:13:32