8 #define deg2rad(x)((x)*M_PI/180) 9 #define rad2deg(rad) (rad * 180 / M_PI) 10 #define eps_eq(a, b, c) (fabs((a)-(b)) <= c) 13 const int c = a.rows();
14 const int n = a.cols();
16 for(
int i = 0;
i <
c;
i++){
18 for(
int j = 0;
j < n;
j++){
19 out <<
" " << std::setw(7) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << (
a)(
i,
j);
27 const int n = a.size();
29 for(
int i = 0;
i < n;
i++){
30 out << std::setw(7) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
a(
i) <<
" ";
49 const int c = _a.rows();
50 const int n = _a.cols();
52 if ( _w.cols() != n || _w.rows() != n ) {
53 _w = dmatrix::Identity(n, n);
58 a1 = (_a * _w * at + _sr_ratio * dmatrix::Identity(c,c)).
inverse();
70 using ::std::numeric_limits;
72 double alpha = (r(0,0) + r(1,1) + r(2,2) - 1.0) / 2.0;
74 if(fabs(alpha - 1.0) < 1.0e-12) {
75 return Vector3::Zero();
77 double th = acos(alpha);
80 if (s < numeric_limits<double>::epsilon()) {
81 return Vector3( sqrt((r(0,0)+1)*0.5)*th, sqrt((r(1,1)+1)*0.5)*th, sqrt((r(2,2)+1)*0.5)*th );
84 double k = -0.5 * th / s;
86 return Vector3( (r(1,2) - r(2,1)) * k,
87 (r(2,0) - r(0,2)) * k,
88 (r(0,1) - r(1,0)) * k );
92 JointPathEx::JointPathEx(
BodyPtr&
robot,
Link* base,
Link* end,
double control_cycle,
bool _use_inside_joint_weight_retrieval,
const std::string& _debug_print_prefix)
93 :
JointPath(base, end), maxIKPosErrorSqr(1.0e-8), maxIKRotErrorSqr(1.0e-6), maxIKIteration(50), interlocking_joint_pair_indices(), sr_gain(1.0), manipulability_limit(0.1), manipulability_gain(0.001), dt(control_cycle),
94 debug_print_prefix(_debug_print_prefix+
",JointPathEx"), joint_limit_debug_print_counts(numJoints(), 0),
95 debug_print_freq_count(static_cast<size_t>(0.25/dt)),
96 use_inside_joint_weight_retrieval(_use_inside_joint_weight_retrieval) {
123 std::vector< std::pair<size_t, size_t> > tmp_vec;
124 for (
size_t i = 0;
i < pairs.size();
i++) {
125 std::pair<size_t, size_t> tmp_pair;
126 bool is_first_ok =
false, is_second_ok =
false;
127 for (
size_t j = 0;
j <
joints.size();
j++) {
131 }
else if (
joints[
j]->
name == pairs[i].second->name) {
136 if (is_first_ok && is_second_ok) tmp_vec.push_back(tmp_pair);
138 if (tmp_vec.size() > 0) {
139 std::cerr <<
"[" << print_str <<
"] Interlocking_joint_pair_indices is set => ";
140 for (
size_t j = 0;
j < tmp_vec.size();
j++) {
141 std::cerr <<
"[" <<
joints[tmp_vec[
j].first]->name <<
", " <<
joints[tmp_vec[
j].second]->name <<
"] ";
143 std::cerr << std::endl;
146 std::cerr <<
"[" << print_str <<
"] No interlocking_joint_pair_indices set." << std::endl;
176 for (
int j = 0;
j < n ;
j++ ) {
178 double jmax =
joints[
j]->ulimit;
179 double jmin =
joints[
j]->llimit;
182 }
else if (
eps_eq(jang, jmax,e) ) {
184 }
else if (
eps_eq(jang, jmin,e) ) {
192 r = fabs( (pow((jmax - jmin),2) * (( 2 * jang) - jmax - jmin)) /
193 (4 * pow((jmax - jang),2) * pow((jang - jmin),2)) );
194 if (std::isnan(r)) r = 0;
210 std::cerr <<
" cost :";
211 for(
int j = 0;
j < n;
j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
avoid_weight_gain[
j]; }
212 std::cerr << std::endl;
213 std::cerr <<
" optw :";
214 for(
int j = 0;
j < n;
j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
optional_weight_vector[
j]; }
215 std::cerr << std::endl;
217 for(
int j = 0;
j < n;
j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << w(
j,
j); }
218 std::cerr << std::endl;
221 double manipulability = sqrt((J*J.transpose()).determinant());
227 std::cerr <<
" manipulability = " << manipulability <<
" < " <<
manipulability_limit <<
", k = " << k <<
" -> " <<
sr_gain * k << std::endl;
232 Jnull = ( hrp::dmatrix::Identity(n, n) - Jinv * J);
238 const double LAMBDA,
const double avoid_gain,
const double reference_gain,
const hrp::dvector* reference_q) {
242 std::cerr <<
"angle :";
243 for(
int j=0;
j < n; ++
j){
244 std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
rad2deg(
joints[
j]->q);
249 size_t ee_workspace_dim = 6;
251 size_t workspace_dim = ee_workspace_dim + ij_workspace_dim;
260 if (ij_workspace_dim > 0) {
261 v << dp, omega, dvector::Zero(ij_workspace_dim);
265 for (
size_t i = 0;
i < ij_workspace_dim;
i++) {
267 ij_J(
i, pair.first) = 1;
268 ij_J(
i, pair.second) = -1;
280 for(
int j=0;
j < v.size(); ++
j){
281 std::cerr <<
" " << v(
j);
283 std::cerr << std::endl;
284 std::cerr <<
" J :" << std::endl << J;
285 std::cerr <<
" Jinv :" << std::endl << Jinv;
288 if ( avoid_gain > 0.0 ) {
294 for (
int j = 0;
j < n ;
j++ ) {
298 double r = ((( (jmax + jmin) / 2.0) - jang) / ((jmax - jmin) / 2.0));
299 if ( r > 0 ) { r = r*r; }
else { r = - r*r; }
303 std::cerr <<
" u(jl):";
304 for(
int j=0;
j < n; ++
j){
305 std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
rad2deg(u(
j));
307 std::cerr << std::endl;
308 std::cerr <<
" JN*u :";
310 for(
int j=0;
j < n; ++
j){
311 std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
rad2deg(Jnullu(
j));
313 std::cerr << std::endl;
318 if ( reference_gain > 0.0 && reference_q != NULL ) {
326 std::cerr <<
"u(ref):";
327 for(
int j=0;
j < n; ++
j){
328 std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
rad2deg(u(
j));
330 std::cerr << std::endl;
331 std::cerr <<
" JN*u:";
333 for(
int j=0;
j < n; ++
j){
334 std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
rad2deg(nullu(
j));
336 std::cerr << std::endl;
341 std::cerr <<
" dq :";
342 for(
int j=0;
j < n; ++
j){
343 std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) <<
rad2deg(dq(
j));
345 std::cerr << std::endl;
349 double min_speed_ratio = 1.0;
350 for(
int j=0;
j < n; ++
j){
351 double speed_ratio = 1.0;
353 speed_ratio = fabs(
joints[
j]->lvlimit * dt / dq(
j));
354 }
else if (dq(
j) >
joints[
j]->uvlimit * dt) {
355 speed_ratio = fabs(
joints[
j]->uvlimit * dt / dq(
j));
359 if ( min_speed_ratio < 1.0 ) {
361 std::cerr <<
"spdlmt: ";
362 for(
int j=0;
j < n; ++
j) { std::cerr << dq(
j) <<
" "; } std::cerr << std::endl;
364 for(
int j=0;
j < n; ++
j) {
365 dq(
j) = dq(
j) * min_speed_ratio;
368 std::cerr <<
"spdlmt: ";
369 for(
int j=0;
j < n; ++
j) { std::cerr << dq(
j) <<
" "; } std::cerr << std::endl;
374 bool solve_linear_equation =
true;
375 for(
int j=0;
j < n; ++
j){
376 if ( std::isnan(dq(
j)) || std::isinf(dq(
j)) ) {
377 solve_linear_equation =
false;
381 if ( ! solve_linear_equation ) {
387 for(
int j=0;
j < n; ++
j){
394 double midp = (
joints[pair.first]->q +
joints[pair.second]->q)/2.0;
395 joints[pair.first]->q = midp;
396 joints[pair.second]->q = midp;
400 for(
int j=0;
j < n; ++
j){
401 bool is_limit_over =
false;
403 is_limit_over =
true;
411 is_limit_over =
true;
438 Eigen::Quaternion<double> eiq(m);
443 if ((q0 > 1.0e-10) || (q0 < -1.0e-10)) {
444 th = 2 * std::atan(norm / q0);
450 mlog = (th / norm) * q ;
452 mlog = hrp::Vector3::Zero();
458 const double LAMBDA,
const double avoid_gain,
const double reference_gain,
const hrp::dvector* reference_q,
459 const double vel_gain,
462 hrp::Matrix33 target_link_R(end_effector_R * localR.transpose());
463 hrp::Vector3 target_link_p(end_effector_p - target_link_R * localPos);
474 const double avoid_gain,
const double reference_gain,
const hrp::dvector* reference_q)
477 static const double LAMBDA = 0.9;
482 if(linkPath.
empty()){
500 for(
int i=0;
i < n; ++
i){
506 double errsqr = DBL_MAX;
507 double errsqr0 = errsqr;
508 bool converged =
false;
511 for(iter = 0; iter < MAX_IK_ITERATION; iter++){
514 std::cerr <<
" iter : " << iter <<
" / " << MAX_IK_ITERATION <<
", n = " << n << std::endl;
519 if ( dp.norm() > 0.1 ) dp = dp*0.1/dp.norm();
520 if ( omega.norm() > 0.5 ) omega = omega*0.5/omega.norm();
524 std::cerr <<
" dp : " << dp[0] <<
" " << dp[1] <<
" " << dp[2] << std::endl;
525 std::cerr <<
"omega : " << omega[0] <<
" " << omega[1] <<
" " << omega[2] << std::endl;
528 std::cerr <<
" err : dp = " << dp.dot(dp) <<
", omega = " << omega.dot(omega) << std::endl;
533 errsqr = dp.dot(dp) + omega.dot(omega);
534 if (
DEBUG ) std::cerr <<
" err : fabs(" << std::setw(18) << std::setiosflags(std::ios::fixed) << std::setprecision(14) << errsqr <<
" - " << errsqr0 <<
") = " << fabs(errsqr-errsqr0) <<
" < " <<
maxIKErrorSqr <<
" BestEffortIKMode" << std::endl;
540 if (
DEBUG ) std::cerr <<
" err : " << std::setw(18) << std::setiosflags(std::ios::fixed) << std::setprecision(14) << sqrt(dp.dot(dp)) <<
" < " << sqrt(
maxIKPosErrorSqr) <<
", " << std::setw(18) << std::setiosflags(std::ios::fixed) << std::setprecision(14) << sqrt(omega.dot(omega)) <<
" < " << sqrt(
maxIKRotErrorSqr) << std::endl;
552 std::cerr <<
"IK Fail, iter = " << iter << std::endl;
555 const double errsqr = dp.dot(dp) + omega.dot(omega);
557 std::cerr <<
" err : fabs(" << errsqr <<
" - " << errsqr0 <<
") = " << fabs(errsqr-errsqr0) <<
" < " <<
maxIKErrorSqr <<
" BestEffortIKMode" << std::endl;
559 std::cerr <<
" err : " << dp.dot(dp) <<
" ( " << dp[0] <<
" " << dp[1] <<
" " << dp[2] <<
") < " <<
maxIKPosErrorSqr << std::endl;
560 std::cerr <<
" : " << omega.dot(omega) <<
" ( " << omega[0] <<
" " << omega[1] <<
" " << omega[2] <<
") < " <<
maxIKRotErrorSqr << std::endl;
562 for(
int i=0;
i < n; ++
i){
573 const std::string& prop_string,
574 const std::string& instance_name)
577 unsigned int nvforce = virtual_force_sensor.size()/10;
578 for (
unsigned int i=0;
i<nvforce;
i++){
579 std::string
name = virtual_force_sensor[
i*10+0];
581 for (
int j = 0;
j < 7;
j++ ) {
587 p.
localR = Eigen::AngleAxis<double>(tr[6],
hrp::Vector3(tr[3],tr[4],tr[5])).toRotationMatrix();
588 p.
link = m_robot->link(virtual_force_sensor[
i*10+2]);
590 std::cerr <<
"[" << instance_name <<
"] virtual force sensor" << std::endl;
591 std::cerr <<
"[" << instance_name <<
"] name = " << name <<
", parent = " << p.
link->
name <<
", id = " << p.
id << std::endl;
592 std::cerr <<
"[" << instance_name <<
"] localP = " << p.
localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[m]" << std::endl;
593 std::cerr <<
"[" << instance_name <<
"] localR = " << p.
localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
599 const std::string& prop_string,
600 const std::string& instance_name)
603 size_t ij_prop_num = 2;
604 if (interlocking_joints_str.size() > 0) {
605 size_t num = interlocking_joints_str.size()/ij_prop_num;
606 for (
size_t i = 0;
i < num;
i++) {
608 hrp::Link* link1 = m_robot->link(interlocking_joints_str[
i*ij_prop_num]);
609 hrp::Link* link2 = m_robot->link(interlocking_joints_str[
i*ij_prop_num+1]);
610 if (link1 == NULL || link2 == NULL) {
611 std::cerr <<
"[" << instance_name <<
"] No such interlocking joints [" << interlocking_joints_str[
i*ij_prop_num] <<
"], [" << interlocking_joints_str[
i*ij_prop_num+1] <<
"]" << std::endl;
614 std::pair<hrp::Link*, hrp::Link*> pair(link1, link2);
615 pairs.push_back(pair);
621 for(
int i=0;
i<_m_robot->numJoints();
i++)_idsb.
q(
i) = _m_robot->joint(
i)->q;
622 _idsb.
dq = (_idsb.
q - _idsb.
q_old) / _idsb.
DT;
625 _idsb.
base_p = _m_robot->rootLink()->p;
628 _idsb.
base_R = _m_robot->rootLink()->R;
636 for(
int i=0;
i<_m_robot->numJoints();
i++){
637 _m_robot->joint(
i)->dq = _idsb.
dq(
i);
638 _m_robot->joint(
i)->ddq = _idsb.
ddq(
i);
642 _m_robot->rootLink()->w = _idsb.
base_w;
643 _m_robot->rootLink()->dw = _idsb.
base_dw;
644 _m_robot->calcForwardKinematics(
true,
true);
645 _m_robot->calcInverseDynamics(_m_robot->rootLink(), _f_ans, _t_ans);
651 _zmp_ans(0) = -t_tmp(1)/f_tmp(2);
652 _zmp_ans(1) = t_tmp(0)/f_tmp(2);
bool calcJacobianInverseNullspace(dmatrix &J, dmatrix &Jinv, dmatrix &Jnull)
std::vector< Link * > joints
void readInterlockingJointsParamFromProperties(std::vector< std::pair< Link *, Link * > > &pairs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
bool stringTo(To &val, const char *str)
png_infop png_charpp name
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
std::ostream & operator<<(std::ostream &out, hrp::dmatrix &a)
std::vector< std::pair< size_t, size_t > > interlocking_joint_pair_indices
OpenHRP::matrix33 Matrix33
dmatrix inverse(const dmatrix &M)
std::vector< double > avoid_weight_gain
void calcRootLinkWrenchFromInverseDynamics(hrp::BodyPtr _m_robot, InvDynStateBuffer &_idsb, hrp::Vector3 &_f_ans, hrp::Vector3 &_t_ans)
bool setInterlockingJointPairIndices(const std::vector< std::pair< Link *, Link * > > &pairs, const std::string &print_str="")
std::vector< std::string > vstring
void setMaxIKIteration(int iter)
void calcJacobian(dmatrix &out_J, const Vector3 &local_p=Vector3::Zero()) const
void calcAccelerationsForInverseDynamics(const hrp::BodyPtr _m_robot, InvDynStateBuffer &_idsb)
void calcForwardKinematics(bool calcVelocity=false, bool calcAcceleration=false) const
std::vector< size_t > joint_limit_debug_print_counts
hrp::Vector3 matrix_logEx(const hrp::Matrix33 &m)
def j(str, encoding="cp932")
int calcSRInverse(const dmatrix &_a, dmatrix &_a_sr, double _sr_ratio, dmatrix _w)
bool calcInverseKinematics2(const Vector3 &end_p, const Matrix33 &end_R, const double avoid_gain=0.0, const double reference_gain=0.0, const dvector *reference_q=NULL)
void getInterlockingJointPairIndices(std::vector< std::pair< size_t, size_t > > &pairs)
Link * joint(int index) const
hrp::Vector3 base_p_oldold
unsigned int numJoints() const
bool use_inside_joint_weight_retrieval
double manipulability_gain
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
void setMaxIKError(double epos, double erot)
std::string debug_print_prefix
Vector3 omegaFromRotEx(const Matrix33 &r)
bool calcInverseKinematics2Loop(const Vector3 &dp, const Vector3 &omega, const double LAMBDA, const double avoid_gain=0.0, const double reference_gain=0.0, const dvector *reference_q=NULL)
std::vector< double > optional_weight_vector
void updateInvDynStateBuffer(InvDynStateBuffer &_idsb)
size_t debug_print_freq_count
double manipulability_limit
void calcWorldZMPFromInverseDynamics(hrp::BodyPtr _m_robot, InvDynStateBuffer &_idsb, hrp::Vector3 &_zmp_ans)