kinematic_extension_dof.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 <limits>
00019 #include <eigen_conversions/eigen_kdl.h>
00020 #include "cob_twist_controller/kinematic_extensions/kinematic_extension_dof.h"
00021 
00022 /* BEGIN KinematicExtensionDOF ********************************************************************************************/
00031 KDL::Jacobian KinematicExtensionDOF::adjustJacobianDof(const KDL::Jacobian& jac_chain, const KDL::Frame eb_frame_ct, const KDL::Frame cb_frame_eb, const ActiveCartesianDimension active_dim)
00032 {
00034     KDL::Jacobian jac_full;
00035 
00036     // jacobian matrix for the extension
00037     Eigen::Matrix<double, 6, Eigen::Dynamic> jac_ext;
00038     jac_ext.resize(6, ext_dof_);
00039     jac_ext.setZero();
00040 
00041     // rotation from base_frame of primary chain to base_frame of extension (eb)
00042     Eigen::Quaterniond quat_cb;
00043     tf::quaternionKDLToEigen(cb_frame_eb.M, quat_cb);
00044     Eigen::Matrix3d rot_cb = quat_cb.toRotationMatrix();
00045 
00047     // omega wrt eb
00048     Eigen::Vector3d w_x_eb(1, 0, 0);
00049     Eigen::Vector3d w_y_eb(0, 1, 0);
00050     Eigen::Vector3d w_z_eb(0, 0, 1);
00051 
00052     // transform to cb
00053     Eigen::Vector3d w_x_cb = quat_cb * w_x_eb;
00054     Eigen::Vector3d w_y_cb = quat_cb * w_y_eb;
00055     Eigen::Vector3d w_z_cb = quat_cb * w_z_eb;
00056 
00058     // vector from base_frame of extension (eb) to endeffector (ct)
00059     Eigen::Vector3d p_eb(eb_frame_ct.p.x(), eb_frame_ct.p.y(), eb_frame_ct.p.z());
00060 
00061     // transform to cb
00062     Eigen::Vector3d p_cb = quat_cb * p_eb;
00063 
00064     // Calculate tangential velocity
00065     Eigen::Vector3d vel_x_cb = w_x_cb.cross(p_cb);
00066     Eigen::Vector3d vel_y_cb = w_y_cb.cross(p_cb);
00067     Eigen::Vector3d vel_z_cb = w_z_cb.cross(p_cb);
00068 
00070     // effect of lin_x motion
00071     jac_ext(0, 0) = rot_cb(0, 0) * active_dim.lin_x;
00072     jac_ext(1, 0) = rot_cb(1, 0) * active_dim.lin_x;
00073     jac_ext(2, 0) = rot_cb(2, 0) * active_dim.lin_x;
00074     jac_ext(3, 0) = 0.0;
00075     jac_ext(4, 0) = 0.0;
00076     jac_ext(5, 0) = 0.0;
00077 
00078     // effect of lin_y motion
00079     jac_ext(0, 1) = rot_cb(0, 1) * active_dim.lin_y;
00080     jac_ext(1, 1) = rot_cb(1, 1) * active_dim.lin_y;
00081     jac_ext(2, 1) = rot_cb(2, 1) * active_dim.lin_y;
00082     jac_ext(3, 1) = 0.0;
00083     jac_ext(4, 1) = 0.0;
00084     jac_ext(5, 1) = 0.0;
00085 
00086     // effect of lin_z motion
00087     jac_ext(0, 2) = rot_cb(0, 2) * active_dim.lin_z;
00088     jac_ext(1, 2) = rot_cb(1, 2) * active_dim.lin_z;
00089     jac_ext(2, 2) = rot_cb(2, 2) * active_dim.lin_z;
00090     jac_ext(3, 2) = 0.0;
00091     jac_ext(4, 2) = 0.0;
00092     jac_ext(5, 2) = 0.0;
00093 
00094     // effect of rot_x motion
00095     jac_ext(0, 3) = vel_x_cb(0) * active_dim.rot_x;
00096     jac_ext(1, 3) = vel_x_cb(1) * active_dim.rot_x;
00097     jac_ext(2, 3) = vel_x_cb(2) * active_dim.rot_x;
00098     jac_ext(3, 3) = w_x_cb(0) * active_dim.rot_x;
00099     jac_ext(4, 3) = w_x_cb(1) * active_dim.rot_x;
00100     jac_ext(5, 3) = w_x_cb(2) * active_dim.rot_x;
00101 
00102     // effect of rot_y motion
00103     jac_ext(0, 4) = vel_y_cb(0) * active_dim.rot_y;
00104     jac_ext(1, 4) = vel_y_cb(1) * active_dim.rot_y;
00105     jac_ext(2, 4) = vel_y_cb(2) * active_dim.rot_y;
00106     jac_ext(3, 4) = w_y_cb(0) * active_dim.rot_y;
00107     jac_ext(4, 4) = w_y_cb(1) * active_dim.rot_y;
00108     jac_ext(5, 4) = w_y_cb(2) * active_dim.rot_y;
00109 
00110     // effect of rot_z motion
00111     jac_ext(0, 5) = vel_z_cb(0) * active_dim.rot_z;
00112     jac_ext(1, 5) = vel_z_cb(1) * active_dim.rot_z;
00113     jac_ext(2, 5) = vel_z_cb(2) * active_dim.rot_z;
00114     jac_ext(3, 5) = w_z_cb(0) * active_dim.rot_z;
00115     jac_ext(4, 5) = w_z_cb(1) * active_dim.rot_z;
00116     jac_ext(5, 5) = w_z_cb(2) * active_dim.rot_z;
00117 
00118     // scale with extension_ratio
00119     jac_ext *= params_.extension_ratio;
00120 
00121     // combine Jacobian of primary chain and extension
00122     Matrix6Xd_t jac_full_matrix;
00123     jac_full_matrix.resize(6, jac_chain.data.cols() + jac_ext.cols());
00124     jac_full_matrix << jac_chain.data, jac_ext;
00125     jac_full.resize(jac_chain.data.cols() + jac_ext.cols());
00126     jac_full.data << jac_full_matrix;
00127 
00128     return jac_full;
00129 }
00130 /* END KinematicExtensionDOF **********************************************************************************************/
00131 
00132 
00133 /* BEGIN KinematicExtensionBaseActive ********************************************************************************************/
00134 bool KinematicExtensionBaseActive::initExtension()
00135 {
00136     this->ext_dof_ = 6;
00137     this->joint_states_.last_q_.resize(ext_dof_);
00138     this->joint_states_.last_q_dot_.resize(ext_dof_);
00139     this->joint_states_.current_q_.resize(ext_dof_);
00140     this->joint_states_.current_q_dot_.resize(ext_dof_);
00141 
00142     for (unsigned int i = 0; i < ext_dof_; i++)
00143     {
00144         limits_max_.push_back(std::numeric_limits<double>::max());
00145         limits_min_.push_back(-std::numeric_limits<double>::max());
00146         if (i < 3)
00147         {
00148             limits_vel_.push_back(max_vel_lin_base_);
00149         }
00150         else
00151         {
00152             limits_vel_.push_back(max_vel_rot_base_);
00153         }
00154         limits_acc_.push_back(std::numeric_limits<double>::max());
00155     }
00156 
00157     return true;
00158 }
00159 
00163 KDL::Jacobian KinematicExtensionBaseActive::adjustJacobian(const KDL::Jacobian& jac_chain)
00164 {
00165     tf::StampedTransform bl_transform_ct, cb_transform_bl;
00166     KDL::Frame bl_frame_ct, cb_frame_bl;
00167     ActiveCartesianDimension active_dim;
00168 
00170     try
00171     {
00172         ros::Time now = ros::Time(0);
00173         tf_listener_.waitForTransform("base_link", params_.chain_tip_link, now, ros::Duration(0.5));
00174         tf_listener_.lookupTransform("base_link", params_.chain_tip_link,  now, bl_transform_ct);
00175 
00176         tf_listener_.waitForTransform(params_.chain_base_link, "base_link", now, ros::Duration(0.5));
00177         tf_listener_.lookupTransform(params_.chain_base_link, "base_link", now, cb_transform_bl);
00178     }
00179     catch (tf::TransformException& ex)
00180     {
00181         ROS_ERROR("%s", ex.what());
00182     }
00183 
00184     bl_frame_ct.p = KDL::Vector(bl_transform_ct.getOrigin().x(), bl_transform_ct.getOrigin().y(), bl_transform_ct.getOrigin().z());
00185     bl_frame_ct.M = KDL::Rotation::Quaternion(bl_transform_ct.getRotation().x(), bl_transform_ct.getRotation().y(), bl_transform_ct.getRotation().z(), bl_transform_ct.getRotation().w());
00186 
00187     cb_frame_bl.p = KDL::Vector(cb_transform_bl.getOrigin().x(), cb_transform_bl.getOrigin().y(), cb_transform_bl.getOrigin().z());
00188     cb_frame_bl.M = KDL::Rotation::Quaternion(cb_transform_bl.getRotation().x(), cb_transform_bl.getRotation().y(), cb_transform_bl.getRotation().z(), cb_transform_bl.getRotation().w());
00189 
00191     active_dim.lin_x = 1;
00192     active_dim.lin_y = 1;
00193     active_dim.lin_z = 0;
00194 
00195     active_dim.rot_x = 0;
00196     active_dim.rot_y = 0;
00197     active_dim.rot_z = 1;
00198 
00199     return adjustJacobianDof(jac_chain, bl_frame_ct, cb_frame_bl, active_dim);
00200 }
00201 
00205 JointStates KinematicExtensionBaseActive::adjustJointStates(const JointStates& joint_states)
00206 {
00207     JointStates js;
00208     unsigned int chain_dof = joint_states.current_q_.rows();
00209     js.current_q_.resize(chain_dof + ext_dof_);
00210     js.last_q_.resize(chain_dof + ext_dof_);
00211     js.current_q_dot_.resize(chain_dof + ext_dof_);
00212     js.last_q_dot_.resize(chain_dof + ext_dof_);
00213 
00214     for (unsigned int i = 0; i< chain_dof; i++)
00215     {
00216         js.current_q_(i) = joint_states.current_q_(i);
00217         js.last_q_(i) = joint_states.last_q_(i);
00218         js.current_q_dot_(i) = joint_states.current_q_dot_(i);
00219         js.last_q_dot_(i) = joint_states.last_q_dot_(i);
00220     }
00221     for (unsigned int i = 0; i < ext_dof_; i++)
00222     {
00223         js.current_q_(chain_dof + i) = 0.0;
00224         js.last_q_(chain_dof + i) = 0.0;
00225         js.current_q_dot_(chain_dof + i) = 0.0;
00226         js.last_q_dot_(chain_dof + i) = 0.0;
00227     }
00228     return js;
00229 }
00230 
00234 LimiterParams KinematicExtensionBaseActive::adjustLimiterParams(const LimiterParams& limiter_params)
00235 {
00236     LimiterParams lp = limiter_params;
00237     for (unsigned int i = 0; i < ext_dof_; i++)
00238     {
00239         lp.limits_max.push_back(std::numeric_limits<double>::max());
00240         lp.limits_min.push_back(-std::numeric_limits<double>::max());
00241         if (i < 3)
00242         {
00243             lp.limits_vel.push_back(max_vel_lin_base_);
00244         }
00245         else
00246         {
00247             lp.limits_vel.push_back(max_vel_rot_base_);
00248         }
00249         lp.limits_acc.push_back(std::numeric_limits<double>::max());
00250     }
00251     return lp;
00252 }
00253 
00257 void KinematicExtensionBaseActive::processResultExtension(const KDL::JntArray& q_dot_ik)
00258 {
00259     geometry_msgs::Twist base_vel_msg;
00260 
00261     base_vel_msg.linear.x = (std::fabs(q_dot_ik(params_.dof)) < min_vel_lin_base_) ? 0.0 : q_dot_ik(params_.dof);
00262     base_vel_msg.linear.y = (std::fabs(q_dot_ik(params_.dof+1)) < min_vel_lin_base_) ? 0.0 : q_dot_ik(params_.dof+1);
00263     base_vel_msg.linear.z = (std::fabs(q_dot_ik(params_.dof+2)) < min_vel_lin_base_) ? 0.0 : q_dot_ik(params_.dof+2);
00264     base_vel_msg.angular.x = (std::fabs(q_dot_ik(params_.dof+3)) < min_vel_rot_base_) ? 0.0 : q_dot_ik(params_.dof+3);
00265     base_vel_msg.angular.y = (std::fabs(q_dot_ik(params_.dof+4)) < min_vel_rot_base_) ? 0.0 : q_dot_ik(params_.dof+4);
00266     base_vel_msg.angular.z = (std::fabs(q_dot_ik(params_.dof+5)) < min_vel_rot_base_) ? 0.0 : q_dot_ik(params_.dof+5);
00267 
00268     base_vel_pub_.publish(base_vel_msg);
00269 }
00270 /* END KinematicExtensionBaseActive **********************************************************************************************/
00271 


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