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");
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;
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;
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);
bool getKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
#define ROS_INFO_STREAM_THROTTLE(period, args)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist &bounds=KDL::Twist::Zero())
unsigned int getNrOfJoints() const
void test(ros::NodeHandle &nh, double num_samples, std::string chain_start, std::string chain_end, double timeout, std::string urdf_param)
double fRand(double min, double max)
bool getKDLChain(KDL::Chain &chain_)
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)