main.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 #include <rdf_loader/rdf_loader.h>
00039 
00040 #include <planning_models/robot_model.h>
00041 #include <planning_models/kinematic_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 
00072  planning_models::RobotModelPtr kinematic_model;
00073  robot_model.reset(new planning_models::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
00074 
00075  planning_models::RobotState *Ptr kinematic_state;
00076  kinematic_state.reset(new planning_models::RobotState(kinematic_model));
00077  kinematic_state->setToDefaultValues();
00078 
00079  planning_models::RobotState *::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("right_arm");
00080 
00081  std::string link_name = "r_wrist_roll_link";
00082  std::vector<double> joint_angles(7,0.0);
00083  geometry_msgs::Point ref_position;
00084  Eigen::MatrixXd jacobian;
00085  Eigen::Vector3d point(0.0,0.0,0.0);
00086  joint_state_group->setStateValues(joint_angles);
00087  ASSERT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00088 
00089  KDL::Tree tree;
00090  if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
00091  {
00092    ROS_ERROR("Could not initialize tree object");
00093  }
00094  KDL::Chain kdl_chain;
00095  std::string base_frame("torso_lift_link");
00096  std::string tip_frame("r_wrist_roll_link");
00097  if (!tree.getChain(base_frame, tip_frame, kdl_chain))
00098  {
00099    ROS_ERROR("Could not initialize chain object");
00100  }
00101  KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
00102  KDL::Jacobian jacobian_kdl(7);
00103  KDL::JntArray q_in(7);
00104  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00105 
00106  unsigned int NUM_TESTS = 1000000;
00107  for(unsigned int i=0; i < NUM_TESTS; i++)
00108  {
00109    for(int j=0; j < 7; j++)
00110    {
00111      q_in(j) = gen_rand(-M_PI,M_PI);
00112      joint_angles[j] = q_in(j);
00113    }
00114    EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00115    joint_state_group->setStateValues(joint_angles);
00116    EXPECT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00117    for(unsigned int k=0; k < 6; k++)
00118    {
00119      for(unsigned int m=0; m < 7; m++)
00120      {
00121        EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
00122      }
00123    }
00124  }
00125 }
00126 
00127 TEST(JacobianSolver, solver2)
00128 {
00129  srand ( time(NULL) ); // initialize random seed:
00130  rdf_loader::RDFLoader model_loader("robot_description");
00131 
00132  planning_models::RobotModelPtr kinematic_model;
00133  robot_model.reset(new planning_models::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
00134 
00135  planning_models::RobotState *Ptr kinematic_state;
00136  kinematic_state.reset(new planning_models::RobotState(kinematic_model));
00137  kinematic_state->setToDefaultValues();
00138 
00139  planning_models::RobotState *::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("left_arm");
00140 
00141  std::string link_name = "l_wrist_roll_link";
00142  std::vector<double> joint_angles(7,0.0);
00143  geometry_msgs::Point ref_position;
00144  Eigen::MatrixXd jacobian;
00145  Eigen::Vector3d point(0.0,0.0,0.0);
00146  joint_state_group->setStateValues(joint_angles);
00147  ASSERT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00148 
00149  KDL::Tree tree;
00150  if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
00151  {
00152    ROS_ERROR("Could not initialize tree object");
00153  }
00154  KDL::Chain kdl_chain;
00155  std::string base_frame("torso_lift_link");
00156  std::string tip_frame("l_wrist_roll_link");
00157  if (!tree.getChain(base_frame, tip_frame, kdl_chain))
00158  {
00159    ROS_ERROR("Could not initialize chain object");
00160  }
00161  KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
00162  KDL::Jacobian jacobian_kdl(7);
00163  KDL::JntArray q_in(7);
00164  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00165 
00166  unsigned int NUM_TESTS = 1000000;
00167  for(unsigned int i=0; i < NUM_TESTS; i++)
00168  {
00169    for(int j=0; j < 7; j++)
00170    {
00171      q_in(j) = gen_rand(-M_PI,M_PI);
00172      joint_angles[j] = q_in(j);
00173    }
00174    EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00175    joint_state_group->setStateValues(joint_angles);
00176    EXPECT_TRUE(joint_state_group->getJacobian(link_name,point,jacobian));
00177    for(unsigned int k=0; k < 6; k++)
00178    {
00179      for(unsigned int m=0; m < 7; m++)
00180      {
00181        EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
00182      }
00183    }
00184  }
00185 }
00186 
00187 
00188 int main(int argc, char **argv)
00189 {
00190   testing::InitGoogleTest(&argc, argv);
00191   ros::init(argc, argv, "test_jacobian_solver");
00192   return RUN_ALL_TESTS();
00193 }


pr2_jacobian_tests
Author(s): Sachin Chitta
autogenerated on Mon Oct 6 2014 11:16:41