00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
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
00049
00050
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;
00055
00056 bool valid = tracik_solver.getKDLChain(chain);
00057
00058 if (!valid) {
00059 ROS_ERROR("There was no valid KDL chain found");
00060 return;
00061 }
00062
00063 valid = tracik_solver.getKDLLimits(ll,ul);
00064
00065 if (!valid) {
00066 ROS_ERROR("There were no valid KDL joint limits found");
00067 return;
00068 }
00069
00070 assert(chain.getNrOfJoints() == ll.data.size());
00071 assert(chain.getNrOfJoints() == ul.data.size());
00072
00073 ROS_INFO ("Using %d joints",chain.getNrOfJoints());
00074
00075
00076
00077 KDL::ChainFkSolverPos_recursive fk_solver(chain);
00078 KDL::ChainIkSolverVel_pinv vik_solver(chain);
00079 KDL::ChainIkSolverPos_NR_JL kdl_solver(chain,ll,ul,fk_solver, vik_solver, 1, eps);
00080
00081
00082
00083
00084 KDL::JntArray nominal(chain.getNrOfJoints());
00085
00086 for (uint j=0; j<nominal.data.size(); j++) {
00087 nominal(j) = (ll(j)+ul(j))/2.0;
00088 }
00089
00090
00091 std::vector<KDL::JntArray> JointList;
00092 KDL::JntArray q(chain.getNrOfJoints());
00093
00094 for (uint i=0; i < num_samples; i++) {
00095 for (uint j=0; j<ll.data.size(); j++) {
00096 q(j)=fRand(ll(j), ul(j));
00097 }
00098 JointList.push_back(q);
00099 }
00100
00101
00102 boost::posix_time::ptime start_time;
00103 boost::posix_time::time_duration diff;
00104
00105 KDL::JntArray result;
00106 KDL::Frame end_effector_pose;
00107 int rc;
00108
00109 double total_time=0;
00110 uint success=0;
00111
00112 ROS_INFO_STREAM("*** Testing KDL with "<<num_samples<<" random samples");
00113
00114 for (uint i=0; i < num_samples; i++) {
00115 fk_solver.JntToCart(JointList[i],end_effector_pose);
00116 double elapsed = 0;
00117 result=nominal;
00118 start_time = boost::posix_time::microsec_clock::local_time();
00119 do {
00120 q=result;
00121 rc=kdl_solver.CartToJnt(q,end_effector_pose,result);
00122 diff = boost::posix_time::microsec_clock::local_time() - start_time;
00123 elapsed = diff.total_nanoseconds() / 1e9;
00124 } while (rc < 0 && elapsed < timeout);
00125 total_time+=elapsed;
00126 if (rc>=0)
00127 success++;
00128
00129 if (int((double)i/num_samples*100)%10 == 0)
00130 ROS_INFO_STREAM_THROTTLE(1,int((i)/num_samples*100)<<"\% done");
00131 }
00132
00133 ROS_INFO_STREAM("KDL found "<<success<<" solutions ("<<100.0*success/num_samples<<"\%) with an average of "<<total_time/num_samples<<" secs per sample");
00134
00135
00136 total_time=0;
00137 success=0;
00138
00139 ROS_INFO_STREAM("*** Testing TRAC-IK with "<<num_samples<<" random samples");
00140
00141 for (uint i=0; i < num_samples; i++) {
00142 fk_solver.JntToCart(JointList[i],end_effector_pose);
00143 double elapsed = 0;
00144 start_time = boost::posix_time::microsec_clock::local_time();
00145 rc=tracik_solver.CartToJnt(nominal,end_effector_pose,result);
00146 diff = boost::posix_time::microsec_clock::local_time() - start_time;
00147 elapsed = diff.total_nanoseconds() / 1e9;
00148 total_time+=elapsed;
00149 if (rc>=0)
00150 success++;
00151
00152 if (int((double)i/num_samples*100)%10 == 0)
00153 ROS_INFO_STREAM_THROTTLE(1,int((i)/num_samples*100)<<"\% done");
00154 }
00155
00156 ROS_INFO_STREAM("TRAC-IK found "<<success<<" solutions ("<<100.0*success/num_samples<<"\%) with an average of "<<total_time/num_samples<<" secs per sample");
00157
00158
00159
00160 }
00161
00162
00163
00164 int main(int argc, char** argv)
00165 {
00166 srand(1);
00167 ros::init(argc, argv, "ik_tests");
00168 ros::NodeHandle nh("~");
00169
00170 int num_samples;
00171 std::string chain_start, chain_end, urdf_param;
00172 double timeout;
00173
00174 nh.param("num_samples", num_samples, 1000);
00175 nh.param("chain_start", chain_start, std::string(""));
00176 nh.param("chain_end", chain_end, std::string(""));
00177
00178 if (chain_start=="" || chain_end=="") {
00179 ROS_FATAL("Missing chain info in launch file");
00180 exit (-1);
00181 }
00182
00183 nh.param("timeout", timeout, 0.005);
00184 nh.param("urdf_param", urdf_param, std::string("/robot_description"));
00185
00186 if (num_samples < 1)
00187 num_samples = 1;
00188
00189 test(nh, num_samples, chain_start, chain_end, timeout, urdf_param);
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201 return 0;
00202 }