31 #include <boost/date_time.hpp>
34 #include <kdl/chainiksolverpos_nr_jl.hpp>
36 double fRand(
double min,
double max)
38 double f = (double)rand() / RAND_MAX;
39 return min +
f * (max - min);
43 void test(
ros::NodeHandle& nh,
double num_samples, std::string chain_start, std::string chain_end,
double timeout, std::string urdf_param)
51 TRAC_IK::TRAC_IK tracik_solver(chain_start, chain_end, urdf_param, timeout, eps);
60 ROS_ERROR(
"There was no valid KDL chain found");
68 ROS_ERROR(
"There were no valid KDL joint limits found");
72 assert(chain.getNrOfJoints() == ll.data.size());
73 assert(chain.getNrOfJoints() == ul.data.size());
75 ROS_INFO(
"Using %d joints", chain.getNrOfJoints());
79 KDL::ChainFkSolverPos_recursive fk_solver(chain);
80 KDL::ChainIkSolverVel_pinv vik_solver(chain);
81 KDL::ChainIkSolverPos_NR_JL kdl_solver(chain, ll, ul, fk_solver, vik_solver, 1, eps);
86 KDL::JntArray nominal(chain.getNrOfJoints());
88 for (uint j = 0; j < nominal.data.size(); j++)
90 nominal(j) = (ll(j) + ul(j)) / 2.0;
94 std::vector<KDL::JntArray> JointList;
95 KDL::JntArray q(chain.getNrOfJoints());
97 for (uint
i = 0;
i < num_samples;
i++)
99 for (uint j = 0; j < ll.data.size(); j++)
101 q(j) =
fRand(ll(j), ul(j));
103 JointList.push_back(q);
107 boost::posix_time::ptime start_time;
108 boost::posix_time::time_duration diff;
110 KDL::JntArray result;
111 KDL::Frame end_effector_pose;
114 double total_time = 0;
117 ROS_INFO_STREAM(
"*** Testing KDL with " << num_samples <<
" random samples");
119 for (uint
i = 0;
i < num_samples;
i++)
121 fk_solver.JntToCart(JointList[
i], end_effector_pose);
124 start_time = boost::posix_time::microsec_clock::local_time();
128 rc = kdl_solver.CartToJnt(q, end_effector_pose, result);
129 diff = boost::posix_time::microsec_clock::local_time() - start_time;
130 elapsed = diff.total_nanoseconds() / 1e9;
132 while (rc < 0 && elapsed < timeout);
133 total_time += elapsed;
137 if (
int((
double)
i / num_samples * 100) % 10 == 0)
141 ROS_INFO_STREAM(
"KDL found " << success <<
" solutions (" << 100.0 * success / num_samples <<
"\%) with an average of " << total_time / num_samples <<
" secs per sample");
147 ROS_INFO_STREAM(
"*** Testing TRAC-IK with " << num_samples <<
" random samples");
149 for (uint
i = 0;
i < num_samples;
i++)
151 fk_solver.JntToCart(JointList[
i], end_effector_pose);
153 start_time = boost::posix_time::microsec_clock::local_time();
154 rc = tracik_solver.
CartToJnt(nominal, end_effector_pose, result);
155 diff = boost::posix_time::microsec_clock::local_time() - start_time;
156 elapsed = diff.total_nanoseconds() / 1e9;
157 total_time += elapsed;
161 if (
int((
double)
i / num_samples * 100) % 10 == 0)
165 ROS_INFO_STREAM(
"TRAC-IK found " << success <<
" solutions (" << 100.0 * success / num_samples <<
"\%) with an average of " << total_time / num_samples <<
" secs per sample");
173 int main(
int argc,
char** argv)
180 std::string chain_start, chain_end, urdf_param;
183 nh.
param(
"num_samples", num_samples, 1000);
184 nh.
param(
"chain_start", chain_start, std::string(
""));
185 nh.
param(
"chain_end", chain_end, std::string(
""));
187 if (chain_start ==
"" || chain_end ==
"")
189 ROS_FATAL(
"Missing chain info in launch file");
193 nh.
param(
"timeout", timeout, 0.005);
194 nh.
param(
"urdf_param", urdf_param, std::string(
"/robot_description"));
199 test(nh, num_samples, chain_start, chain_end, timeout, urdf_param);