ik_tests.cpp
Go to the documentation of this file.
00001 /********************************************************************************
00002 Copyright (c) 2016, TRACLabs, Inc.
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006  are permitted provided that the following conditions are met:
00007 
00008     1. Redistributions of source code must retain the above copyright notice,
00009        this list of conditions and the following disclaimer.
00010 
00011     2. Redistributions in binary form must reproduce the above copyright notice,
00012        this list of conditions and the following disclaimer in the documentation
00013        and/or other materials provided with the distribution.
00014 
00015     3. Neither the name of the copyright holder nor the names of its contributors
00016        may be used to endorse or promote products derived from this software
00017        without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
00023 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00025 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00027 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
00028 OF THE POSSIBILITY OF SUCH DAMAGE.
00029 ********************************************************************************/
00030 
00031 #include <boost/date_time.hpp>
00032 #include <trac_ik/trac_ik.hpp>
00033 #include <ros/ros.h>
00034 #include <kdl/chainiksolverpos_nr_jl.hpp>
00035 
00036 double fRand(double min, double max)
00037 {
00038   double f = (double)rand() / RAND_MAX;
00039   return min + f * (max - min);
00040 }
00041 
00042 
00043 void test(ros::NodeHandle& nh, double num_samples, std::string chain_start, std::string chain_end, double timeout, std::string urdf_param)
00044 {
00045 
00046   double eps = 1e-5;
00047 
00048   // This constructor parses the URDF loaded in rosparm urdf_param into the
00049   // needed KDL structures.  We then pull these out to compare against the KDL
00050   // IK solver.
00051   TRAC_IK::TRAC_IK tracik_solver(chain_start, chain_end, urdf_param, timeout, eps);
00052 
00053   KDL::Chain chain;
00054   KDL::JntArray ll, ul; //lower joint limits, upper joint limits
00055 
00056   bool valid = tracik_solver.getKDLChain(chain);
00057 
00058   if (!valid)
00059   {
00060     ROS_ERROR("There was no valid KDL chain found");
00061     return;
00062   }
00063 
00064   valid = tracik_solver.getKDLLimits(ll, ul);
00065 
00066   if (!valid)
00067   {
00068     ROS_ERROR("There were no valid KDL joint limits found");
00069     return;
00070   }
00071 
00072   assert(chain.getNrOfJoints() == ll.data.size());
00073   assert(chain.getNrOfJoints() == ul.data.size());
00074 
00075   ROS_INFO("Using %d joints", chain.getNrOfJoints());
00076 
00077 
00078   // Set up KDL IK
00079   KDL::ChainFkSolverPos_recursive fk_solver(chain); // Forward kin. solver
00080   KDL::ChainIkSolverVel_pinv vik_solver(chain); // PseudoInverse vel solver
00081   KDL::ChainIkSolverPos_NR_JL kdl_solver(chain, ll, ul, fk_solver, vik_solver, 1, eps); // Joint Limit Solver
00082   // 1 iteration per solve (will wrap in timed loop to compare with TRAC-IK)
00083 
00084 
00085   // Create Nominal chain configuration midway between all joint limits
00086   KDL::JntArray nominal(chain.getNrOfJoints());
00087 
00088   for (uint j = 0; j < nominal.data.size(); j++)
00089   {
00090     nominal(j) = (ll(j) + ul(j)) / 2.0;
00091   }
00092 
00093   // Create desired number of valid, random joint configurations
00094   std::vector<KDL::JntArray> JointList;
00095   KDL::JntArray q(chain.getNrOfJoints());
00096 
00097   for (uint i = 0; i < num_samples; i++)
00098   {
00099     for (uint j = 0; j < ll.data.size(); j++)
00100     {
00101       q(j) = fRand(ll(j), ul(j));
00102     }
00103     JointList.push_back(q);
00104   }
00105 
00106 
00107   boost::posix_time::ptime start_time;
00108   boost::posix_time::time_duration diff;
00109 
00110   KDL::JntArray result;
00111   KDL::Frame end_effector_pose;
00112   int rc;
00113 
00114   double total_time = 0;
00115   uint success = 0;
00116 
00117   ROS_INFO_STREAM("*** Testing KDL with " << num_samples << " random samples");
00118 
00119   for (uint i = 0; i < num_samples; i++)
00120   {
00121     fk_solver.JntToCart(JointList[i], end_effector_pose);
00122     double elapsed = 0;
00123     result = nominal; // start with nominal
00124     start_time = boost::posix_time::microsec_clock::local_time();
00125     do
00126     {
00127       q = result; // when iterating start with last solution
00128       rc = kdl_solver.CartToJnt(q, end_effector_pose, result);
00129       diff = boost::posix_time::microsec_clock::local_time() - start_time;
00130       elapsed = diff.total_nanoseconds() / 1e9;
00131     }
00132     while (rc < 0 && elapsed < timeout);
00133     total_time += elapsed;
00134     if (rc >= 0)
00135       success++;
00136 
00137     if (int((double)i / num_samples * 100) % 10 == 0)
00138       ROS_INFO_STREAM_THROTTLE(1, int((i) / num_samples * 100) << "\% done");
00139   }
00140 
00141   ROS_INFO_STREAM("KDL found " << success << " solutions (" << 100.0 * success / num_samples << "\%) with an average of " << total_time / num_samples << " secs per sample");
00142 
00143 
00144   total_time = 0;
00145   success = 0;
00146 
00147   ROS_INFO_STREAM("*** Testing TRAC-IK with " << num_samples << " random samples");
00148 
00149   for (uint i = 0; i < num_samples; i++)
00150   {
00151     fk_solver.JntToCart(JointList[i], end_effector_pose);
00152     double elapsed = 0;
00153     start_time = boost::posix_time::microsec_clock::local_time();
00154     rc = tracik_solver.CartToJnt(nominal, end_effector_pose, result);
00155     diff = boost::posix_time::microsec_clock::local_time() - start_time;
00156     elapsed = diff.total_nanoseconds() / 1e9;
00157     total_time += elapsed;
00158     if (rc >= 0)
00159       success++;
00160 
00161     if (int((double)i / num_samples * 100) % 10 == 0)
00162       ROS_INFO_STREAM_THROTTLE(1, int((i) / num_samples * 100) << "\% done");
00163   }
00164 
00165   ROS_INFO_STREAM("TRAC-IK found " << success << " solutions (" << 100.0 * success / num_samples << "\%) with an average of " << total_time / num_samples << " secs per sample");
00166 
00167 
00168 
00169 }
00170 
00171 
00172 
00173 int main(int argc, char** argv)
00174 {
00175   srand(1);
00176   ros::init(argc, argv, "ik_tests");
00177   ros::NodeHandle nh("~");
00178 
00179   int num_samples;
00180   std::string chain_start, chain_end, urdf_param;
00181   double timeout;
00182 
00183   nh.param("num_samples", num_samples, 1000);
00184   nh.param("chain_start", chain_start, std::string(""));
00185   nh.param("chain_end", chain_end, std::string(""));
00186 
00187   if (chain_start == "" || chain_end == "")
00188   {
00189     ROS_FATAL("Missing chain info in launch file");
00190     exit(-1);
00191   }
00192 
00193   nh.param("timeout", timeout, 0.005);
00194   nh.param("urdf_param", urdf_param, std::string("/robot_description"));
00195 
00196   if (num_samples < 1)
00197     num_samples = 1;
00198 
00199   test(nh, num_samples, chain_start, chain_end, timeout, urdf_param);
00200 
00201   // Useful when you make a script that loops over multiple launch files that test different robot chains
00202   // std::vector<char *> commandVector;
00203   // commandVector.push_back((char*)"killall");
00204   // commandVector.push_back((char*)"-9");
00205   // commandVector.push_back((char*)"roslaunch");
00206   // commandVector.push_back(NULL);
00207 
00208   // char **command = &commandVector[0];
00209   // execvp(command[0],command);
00210 
00211   return 0;
00212 }


trac_ik_examples
Author(s): Patrick Beeson
autogenerated on Thu Apr 25 2019 03:39:25