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 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 void testJacobian(std::string group_name, std::string base_link, std::string tip_link)
00068 {
00069  SCOPED_TRACE(group_name + ": " + base_link + " to " + tip_link);
00070  
00071  srand ( time(NULL) ); // initialize random seed:
00072  rdf_loader::RDFLoader model_loader("robot_description");
00073  robot_model::RobotModelPtr kinematic_model;
00074  kinematic_model.reset(new robot_model::RobotModel(model_loader.getURDF(),model_loader.getSRDF()));
00075 
00076  robot_state::RobotStatePtr kinematic_state;
00077  kinematic_state.reset(new robot_state::RobotState(kinematic_model));
00078  kinematic_state->setToDefaultValues();
00079 
00080  const moveit::core::JointModelGroup* joint_state_group = kinematic_state->getRobotModel()->getJointModelGroup(group_name);
00081 
00082  std::string link_name = tip_link;
00083  std::vector<double> joint_angles(7,0.0);
00084  geometry_msgs::Point ref_position;
00085  Eigen::MatrixXd jacobian;
00086  Eigen::Vector3d point(0.0,0.0,0.0);
00087  kinematic_state->setJointGroupPositions(joint_state_group, &joint_angles[0]);
00088  ASSERT_TRUE(kinematic_state->getJacobian(joint_state_group, kinematic_state->getRobotModel()->getLinkModel(link_name),point,jacobian));
00089 
00090  KDL::Tree tree;
00091  if (!kdl_parser::treeFromUrdfModel(*model_loader.getURDF(), tree))
00092  {
00093    ROS_ERROR("Could not initialize tree object");
00094  }
00095  KDL::Chain kdl_chain;
00096  std::string base_frame(base_link);
00097  std::string tip_frame(tip_link);
00098  if (!tree.getChain(base_frame, tip_frame, kdl_chain))
00099  {
00100    ROS_ERROR("Could not initialize chain object");
00101  }
00102  KDL::ChainJntToJacSolver kdl_solver(kdl_chain);
00103  KDL::Jacobian jacobian_kdl(7);
00104  KDL::JntArray q_in(7);
00105  EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00106 
00107  unsigned int NUM_TESTS = 10000;
00108  for(unsigned int i=0; i < NUM_TESTS; i++)
00109  {
00110    for(int j=0; j < 7; j++)
00111    {
00112      q_in(j) = gen_rand(-M_PI,M_PI);
00113      joint_angles[j] = q_in(j);
00114    }
00115    EXPECT_TRUE(kdl_solver.JntToJac(q_in,jacobian_kdl) >= 0);
00116    kinematic_state->setJointGroupPositions(joint_state_group, &joint_angles[0]);
00117    EXPECT_TRUE(kinematic_state->getJacobian(joint_state_group, kinematic_state->getRobotModel()->getLinkModel(link_name), point, jacobian));
00118    for(unsigned int k=0; k < 6; k++)
00119    {
00120      for(unsigned int m=0; m < 7; m++)
00121      {
00122        EXPECT_FALSE(NOT_NEAR(jacobian_kdl(k,m),jacobian(k,m),1e-10));
00123      }
00124    }
00125  }
00126 }
00127 
00128 TEST(JacobianSolver, solver)
00129 {
00130   testJacobian("right_arm", "torso_lift_link", "r_wrist_roll_link");
00131 }
00132 
00133 TEST(JacobianSolver, solver2)
00134 {
00135   testJacobian("left_arm", "torso_lift_link", "l_wrist_roll_link");
00136 }
00137 
00138 int main(int argc, char **argv)
00139 {
00140   testing::InitGoogleTest(&argc, argv);
00141   ros::init(argc, argv, "test_jacobian_solver");
00142   return RUN_ALL_TESTS();
00143 }


pr2_moveit_tests
Author(s):
autogenerated on Mon Sep 14 2015 14:17:42