33 #include <boost/date_time.hpp> 34 #include <Eigen/Geometry> 43 TRAC_IK::TRAC_IK(
const std::string& base_link,
const std::string& tip_link,
const std::string& URDF_param,
double _maxtime,
double _eps,
SolveType _type) :
53 std::string xml_string;
55 std::string urdf_xml, full_urdf_xml;
56 node_handle.
param(
"urdf_xml", urdf_xml, URDF_param);
60 if (!node_handle.
getParam(full_urdf_xml, xml_string))
62 ROS_FATAL_NAMED(
"trac_ik",
"Could not load the xml from parameter server: %s", urdf_xml.c_str());
66 node_handle.
param(full_urdf_xml, xml_string, std::string());
74 ROS_FATAL(
"Failed to extract kdl tree from xml robot description");
76 if (!tree.
getChain(base_link, tip_link, chain))
77 ROS_FATAL(
"Couldn't find chain %s to %s", base_link.c_str(), tip_link.c_str());
79 std::vector<KDL::Segment> chain_segs = chain.segments;
81 urdf::JointConstSharedPtr joint;
83 std::vector<double> l_bounds, u_bounds;
85 lb.resize(chain.getNrOfJoints());
86 ub.resize(chain.getNrOfJoints());
89 for (
unsigned int i = 0; i < chain_segs.size(); ++i)
91 joint = robot_model.getJoint(chain_segs[i].getJoint().
getName());
92 if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED)
97 if (joint->type != urdf::Joint::CONTINUOUS)
101 lower = std::max(joint->limits->lower, joint->safety->soft_lower_limit);
102 upper = std::min(joint->limits->upper, joint->safety->soft_upper_limit);
106 lower = joint->limits->lower;
107 upper = joint->limits->upper;
117 lb(joint_num - 1) = lower;
118 ub(joint_num - 1) = upper;
122 lb(joint_num - 1) = std::numeric_limits<float>::lowest();
123 ub(joint_num - 1) = std::numeric_limits<float>::max();
125 ROS_DEBUG_STREAM_NAMED(
"trac_ik",
"IK Using joint " << joint->name <<
" " << lb(joint_num - 1) <<
" " << ub(joint_num - 1));
145 void TRAC_IK::initialize()
148 assert(chain.getNrOfJoints() == lb.data.size());
149 assert(chain.getNrOfJoints() == ub.data.size());
155 for (uint i = 0; i < chain.segments.size(); i++)
157 std::string type = chain.segments[i].getJoint().getTypeName();
158 if (type.find(
"Rot") != std::string::npos)
160 if (ub(types.size()) >= std::numeric_limits<float>::max() &&
161 lb(types.size()) <= std::numeric_limits<float>::lowest())
166 else if (type.find(
"Trans") != std::string::npos)
170 assert(types.size() == lb.data.size());
178 for (uint i = 0; i < solutions.size(); i++)
179 if (myEqual(sol, solutions[i]))
190 double diffangle = fmod(val - max, 2 *
M_PI);
192 val = max + diffangle - 2 *
M_PI;
198 double diffangle = fmod(min - val, 2 *
M_PI);
200 val = min - diffangle + 2 *
M_PI;
206 if (val > target +
M_PI)
209 double diffangle = fmod(val - target, 2 *
M_PI);
211 val = target + diffangle - 2 *
M_PI;
214 if (val < target -
M_PI)
217 double diffangle = fmod(target - val, 2 *
M_PI);
219 val = target - diffangle + 2 *
M_PI;
224 template<
typename T1,
typename T2>
225 bool TRAC_IK::runSolver(T1& solver, T2& other_solver,
231 double fulltime = maxtime;
234 boost::posix_time::time_duration timediff;
239 timediff = boost::posix_time::microsec_clock::local_time() - start_time;
240 time_left = fulltime - timediff.total_nanoseconds() / 1000000000.0;
245 solver.setMaxtime(time_left);
247 int RC = solver.CartToJnt(seed, p_in, q_out, bounds);
254 normalize_limits(q_init, q_out);
257 normalize_seed(q_init, q_out);
261 if (unique_solution(q_out))
263 solutions.push_back(q_out);
264 uint curr_size = solutions.size();
265 errors.resize(curr_size);
271 penalty = manipPenalty(q_out);
272 err = penalty * TRAC_IK::ManipValue1(q_out);
275 penalty = manipPenalty(q_out);
276 err = penalty * TRAC_IK::ManipValue2(q_out);
279 err = TRAC_IK::JointErr(q_init, q_out);
283 errors[curr_size - 1] = std::make_pair(err, curr_size - 1);
288 if (!solutions.empty() && solvetype ==
Speed)
291 for (
unsigned int j = 0; j < seed.
data.size(); j++)
293 seed(j) = fRand(q_init(j) - 2 *
M_PI, q_init(j) + 2 *
M_PI);
295 seed(j) = fRand(lb(j), ub(j));
297 other_solver.abort();
299 solver.setMaxtime(fulltime);
310 bool improved =
false;
312 for (uint i = 0; i < lb.data.size(); i++)
318 double target = seed(i);
319 double val = solution(i);
340 bool improved =
false;
342 for (uint i = 0; i < lb.data.size(); i++)
348 double target = seed(i);
351 target = (ub(i) + lb(i)) / 2.0;
353 double val = solution(i);
373 double penalty = 1.0;
374 for (uint i = 0; i < arr.
data.size(); i++)
378 double range = ub(i) - lb(i);
379 penalty *= ((arr(i) - lb(i)) * (ub(i) - arr(i)) / (range * range));
381 return std::max(0.0, 1.0 -
exp(-1 * penalty));
389 jacsolver->JntToJac(arr, jac);
391 Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jac.data);
392 Eigen::MatrixXd singular_values = svdsolver.singularValues();
395 for (
unsigned int i = 0; i < singular_values.rows(); ++i)
396 error *= singular_values(i, 0);
404 jacsolver->JntToJac(arr, jac);
406 Eigen::JacobiSVD<Eigen::MatrixXd> svdsolver(jac.data);
407 Eigen::MatrixXd singular_values = svdsolver.singularValues();
409 return singular_values.minCoeff() / singular_values.maxCoeff();
418 ROS_ERROR(
"TRAC-IK was not properly initialized with a valid chain or limits. IK cannot proceed");
423 start_time = boost::posix_time::microsec_clock::local_time();
433 task1 = std::thread(&TRAC_IK::runKDL,
this, q_init, p_in);
434 task2 = std::thread(&TRAC_IK::runNLOPT,
this, q_init, p_in);
439 if (solutions.empty())
449 std::sort(errors.rbegin(), errors.rend());
452 std::sort(errors.begin(), errors.end());
456 q_out = solutions[errors[0].second];
458 return solutions.size();
464 if (task1.joinable())
466 if (task2.joinable())
#define ROS_DEBUG_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
ROSCONSOLE_DECL void initialize()
std::string getName(void *handle)
#define ROS_DEBUG_NAMED(name,...)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
bool getParam(const std::string &key, std::string &s) const
#define ROS_FATAL_NAMED(name,...)
void normalizeAngle(double &val, const double &min, const double &max)
dual_quaternion exp(dual_quaternion a)