kinematic_extension_lookat.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #include <string>
00019 #include <vector>
00020 #include <limits>
00021 #include <algorithm>
00022 #include <tf_conversions/tf_kdl.h>
00023 #include <eigen_conversions/eigen_kdl.h>
00024 #include "cob_twist_controller/kinematic_extensions/kinematic_extension_lookat.h"
00025 
00026 /* BEGIN KinematicExtensionLookat ********************************************************************************************/
00027 bool KinematicExtensionLookat::initExtension()
00028 {
00030     KDL::Tree tree;
00031     if (!kdl_parser::treeFromParam("robot_description", tree))
00032     {
00033         ROS_ERROR("Failed to construct kdl tree");
00034         return false;
00035     }
00036 
00037     KDL::Chain chain_main;
00038     tree.getChain(params_.chain_base_link, params_.chain_tip_link, chain_main);
00039     if (chain_main.getNrOfJoints() == 0)
00040     {
00041         ROS_ERROR("Failed to initialize kinematic chain");
00042         return false;
00043     }
00044 
00046     KDL::Vector lookat_lin_axis(0.0, 0.0, 0.0);
00047     switch (params_.lookat_offset.lookat_axis_type)
00048     {
00049         case X_POSITIVE:
00050             lookat_lin_axis.x(1.0);
00051             break;
00052         case Y_POSITIVE:
00053             lookat_lin_axis.y(1.0);
00054             break;
00055         case Z_POSITIVE:
00056             lookat_lin_axis.z(1.0);
00057             break;
00058         case X_NEGATIVE:
00059             lookat_lin_axis.x(-1.0);
00060             break;
00061         case Y_NEGATIVE:
00062             lookat_lin_axis.y(-1.0);
00063             break;
00064         case Z_NEGATIVE:
00065             lookat_lin_axis.z(-1.0);
00066             break;
00067         default:
00068             ROS_ERROR("LookatAxisType %d not defined! Using default: 'X_POSITIVE'!", params_.lookat_offset.lookat_axis_type);
00069             lookat_lin_axis.x(1.0);
00070             break;
00071     }
00072     KDL::Joint lookat_lin_joint("lookat_lin_joint", KDL::Vector(), lookat_lin_axis, KDL::Joint::TransAxis);
00073 
00074     KDL::Frame offset;
00075     offset.p = KDL::Vector(params_.lookat_offset.translation_x, params_.lookat_offset.translation_y, params_.lookat_offset.translation_z);
00076     offset.M = KDL::Rotation::Quaternion(params_.lookat_offset.rotation_x, params_.lookat_offset.rotation_y, params_.lookat_offset.rotation_z, params_.lookat_offset.rotation_w);
00077 
00078     KDL::Segment lookat_rotx_link("lookat_rotx_link", lookat_lin_joint, offset);
00079     chain_ext_.addSegment(lookat_rotx_link);
00080     limits_ext_max_.push_back(std::numeric_limits<double>::max());
00081     limits_ext_min_.push_back(-std::numeric_limits<double>::max());
00082     limits_ext_vel_.push_back(5.0);
00083     limits_ext_acc_.push_back(std::numeric_limits<double>::max());
00084 
00085     KDL::Vector lookat_rotx_axis(1.0, 0.0, 0.0);
00086     KDL::Joint lookat_rotx_joint("lookat_rotx_joint", KDL::Vector(), lookat_rotx_axis, KDL::Joint::RotAxis);
00087     KDL::Segment lookat_roty_link("lookat_roty_link", lookat_rotx_joint);
00088     chain_ext_.addSegment(lookat_roty_link);
00089     // limits_ext_max_.push_back(M_PI);
00090     // limits_ext_min_.push_back(-M_PI);
00091     limits_ext_max_.push_back(std::numeric_limits<double>::max());
00092     limits_ext_min_.push_back(-std::numeric_limits<double>::max());
00093     // limits_ext_vel_.push_back(std::numeric_limits<double>::max());
00094     limits_ext_vel_.push_back(M_PI);
00095     limits_ext_acc_.push_back(std::numeric_limits<double>::max());
00096 
00097     KDL::Vector lookat_roty_axis(0.0, 1.0, 0.0);
00098     KDL::Joint lookat_roty_joint("lookat_roty_joint", KDL::Vector(), lookat_roty_axis, KDL::Joint::RotAxis);
00099     KDL::Segment lookat_rotz_link("lookat_rotz_link", lookat_roty_joint);
00100     chain_ext_.addSegment(lookat_rotz_link);
00101     // limits_ext_max_.push_back(M_PI);
00102     // limits_ext_min_.push_back(-M_PI);
00103     limits_ext_max_.push_back(std::numeric_limits<double>::max());
00104     limits_ext_min_.push_back(-std::numeric_limits<double>::max());
00105     // limits_ext_vel_.push_back(std::numeric_limits<double>::max());
00106     limits_ext_vel_.push_back(M_PI);
00107     limits_ext_acc_.push_back(std::numeric_limits<double>::max());
00108 
00109     KDL::Vector lookat_rotz_axis(0.0, 0.0, 1.0);
00110     KDL::Joint lookat_rotz_joint("lookat_rotz_joint", KDL::Vector(), lookat_rotz_axis, KDL::Joint::RotAxis);
00111     KDL::Segment lookat_focus_frame("lookat_focus_frame", lookat_rotz_joint);
00112     chain_ext_.addSegment(lookat_focus_frame);
00113     // limits_ext_max_.push_back(M_PI);
00114     // limits_ext_min_.push_back(-M_PI);
00115     limits_ext_max_.push_back(std::numeric_limits<double>::max());
00116     limits_ext_min_.push_back(-std::numeric_limits<double>::max());
00117     // limits_ext_vel_.push_back(std::numeric_limits<double>::max());
00118     limits_ext_vel_.push_back(M_PI);
00119     limits_ext_acc_.push_back(std::numeric_limits<double>::max());
00120 
00121     chain_full_ = chain_main;
00122     chain_full_.addChain(chain_ext_);
00123 
00124     fk_solver_ext_.reset(new KDL::ChainFkSolverPos_recursive(chain_ext_));
00125     jnt2jac_.reset(new KDL::ChainJntToJacSolver(chain_full_));
00126 
00127     this->ext_dof_ = 4;
00128     this->joint_states_ext_.last_q_.resize(ext_dof_);
00129     KDL::SetToZero(this->joint_states_ext_.last_q_);
00130     this->joint_states_ext_.last_q_dot_.resize(ext_dof_);
00131     KDL::SetToZero(this->joint_states_ext_.last_q_dot_);
00132     this->joint_states_ext_.current_q_.resize(ext_dof_);
00133     KDL::SetToZero(this->joint_states_ext_.current_q_);
00134     this->joint_states_ext_.current_q_dot_.resize(ext_dof_);
00135     KDL::SetToZero(this->joint_states_ext_.current_q_dot_);
00136 
00137     integrator_.reset(new SimpsonIntegrator(ext_dof_, 0.2));  // default smoothing: 0.2
00138 
00139     timer_ = nh_.createTimer(ros::Duration(1/100.0), &KinematicExtensionLookat::broadcastFocusFrame, this);
00140     timer_.start();
00141 
00142     return true;
00143 }
00144 
00145 KDL::Jacobian KinematicExtensionLookat::adjustJacobian(const KDL::Jacobian& jac_chain)
00146 {
00148     boost::mutex::scoped_lock lock(mutex_);
00149     KDL::Jacobian jac_full(chain_full_.getNrOfJoints());
00150 
00151     jnt2jac_->JntToJac(joint_states_full_.current_q_ , jac_full);
00152 
00153     return jac_full;
00154 }
00155 
00156 JointStates KinematicExtensionLookat::adjustJointStates(const JointStates& joint_states)
00157 {
00158     boost::mutex::scoped_lock lock(mutex_);
00159     unsigned int chain_dof = joint_states.current_q_.rows();
00160     joint_states_full_.current_q_.resize(chain_dof + ext_dof_);
00161     joint_states_full_.last_q_.resize(chain_dof + ext_dof_);
00162     joint_states_full_.current_q_dot_.resize(chain_dof + ext_dof_);
00163     joint_states_full_.last_q_dot_.resize(chain_dof + ext_dof_);
00164 
00165     for (unsigned int i = 0; i< chain_dof; i++)
00166     {
00167         joint_states_full_.current_q_(i) = joint_states.current_q_(i);
00168         joint_states_full_.last_q_(i) = joint_states.last_q_(i);
00169         joint_states_full_.current_q_dot_(i) = joint_states.current_q_dot_(i);
00170         joint_states_full_.last_q_dot_(i) = joint_states.last_q_dot_(i);
00171     }
00172     for (unsigned int i = 0; i < ext_dof_; i++)
00173     {
00174         joint_states_full_.current_q_(chain_dof + i) = this->joint_states_ext_.current_q_(i);
00175         joint_states_full_.last_q_(chain_dof + i) = this->joint_states_ext_.last_q_(i);
00176         joint_states_full_.current_q_dot_(chain_dof + i) = this->joint_states_ext_.current_q_dot_(i);
00177         joint_states_full_.last_q_dot_(chain_dof + i) = this->joint_states_ext_.last_q_dot_(i);
00178     }
00179 
00180     return joint_states_full_;
00181 }
00182 
00183 LimiterParams KinematicExtensionLookat::adjustLimiterParams(const LimiterParams& limiter_params)
00184 {
00185     LimiterParams lp = limiter_params;
00186     for (unsigned int i = 0; i < ext_dof_; i++)
00187     {
00188         lp.limits_max.push_back(limits_ext_max_[i]);
00189         lp.limits_min.push_back(limits_ext_min_[i]);
00190         lp.limits_vel.push_back(limits_ext_vel_[i]);
00191         lp.limits_acc.push_back(limits_ext_acc_[i]);
00192     }
00193     return lp;
00194 }
00195 
00196 void KinematicExtensionLookat::processResultExtension(const KDL::JntArray& q_dot_ik)
00197 {
00199     boost::mutex::scoped_lock lock(mutex_);
00200     std::vector<double> pos;
00201     std::vector<double> vel;
00202 
00203     for (unsigned int i = 0; i < ext_dof_; i++)
00204     {
00205         joint_states_ext_.current_q_dot_(i) = q_dot_ik(params_.dof + i);
00206     }
00207 
00208     if (integrator_->updateIntegration(joint_states_ext_.current_q_dot_, joint_states_ext_.current_q_, pos, vel))
00209     {
00210         for (unsigned int i = 0; i < ext_dof_; i++)
00211         {
00212             joint_states_ext_.last_q_(i) = this->joint_states_ext_.current_q_(i);
00213             joint_states_ext_.last_q_dot_(i) = this->joint_states_ext_.current_q_dot_(i);
00214             joint_states_ext_.current_q_(i) = std::max(pos[i], 0.1);  // do not look backwards
00215             joint_states_ext_.current_q_dot_(i) = vel[i];
00216         }
00217     }
00218 }
00219 
00220 void KinematicExtensionLookat::broadcastFocusFrame(const ros::TimerEvent& event)
00221 {
00222     boost::mutex::scoped_lock lock(mutex_);
00223     KDL::Frame focus_frame;
00224 
00225     fk_solver_ext_->JntToCart(joint_states_ext_.current_q_, focus_frame);
00226 
00227     tf::Transform transform;
00228     tf::transformKDLToTF(focus_frame, transform);
00229     br_.sendTransform(tf::StampedTransform(transform, ros::Time::now(), params_.chain_tip_link, "lookat_focus_frame"));
00230 }
00231 
00232 /* END KinematicExtensionLookat ********************************************************************************************/


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26