00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef _uncalibvs_sim_alg_h_
00026 #define _uncalibvs_sim_alg_h_
00027
00028 #include <iri_uncalibvs_sim/Uncalibvs_simConfig.h>
00029 #include "mutex.h"
00030
00031 #include <math.h>
00032 #include <LinearMath/btQuaternion.h>
00033 #include <LinearMath/btMatrix3x3.h>
00034
00035 #include <tf/transform_datatypes.h>
00036
00037
00038 #include <Eigen/Dense>
00039 #include <Eigen/Eigenvalues>
00040 #include <Eigen/SVD>
00041
00042
00043 #include <iostream>
00044 #include <fstream>
00045 #include <stdio.h>
00046
00047 #include <geometry_msgs/Twist.h>
00048 #include <sensor_msgs/JointState.h>
00049 #include <eigen_conversions/eigen_kdl.h>
00050
00051
00052 #include <kdl/frames.hpp>
00053 #include <kdl/frames_io.hpp>
00054 #include <kdl/chain.hpp>
00055 #include <kdl/chainfksolver.hpp>
00056 #include <kdl/chainfksolverpos_recursive.hpp>
00057 #include <kdl/chainiksolver.hpp>
00058 #include <kdl/chainiksolverpos_nr.hpp>
00059 #include <kdl/chainiksolvervel_wdls.hpp>
00060 #include <kdl/frames_io.hpp>
00061
00062 #include <boost/scoped_ptr.hpp>
00063
00064
00065
00072 class Uncalibvs_simAlgorithm
00073 {
00074 protected:
00081 CMutex alg_mutex_;
00082
00083
00084
00085 int n_,noise_;
00086 unsigned int nj_;
00087 double lambda_,final_z_,secs_,phi_old_;
00088 float ff_,ff_old_,u0_,v0_;
00089
00090
00091 Eigen::Matrix3f Rquad_inertial_;
00092 Eigen::Matrix4f T0c_new_,Tc0_,cTo_,T0c_0_,T0c_x_,diTj_int_,V_mod_;
00093 Eigen::MatrixXf lambda_robot_,pj_,pn_,P0_,alfas_,uv_,s_,S_,S_x_,cj_0_,cP_,cP_x_,ccP_,J_,diff_,V2_,Vel_,Vqa0_,QQ_,Jqa_,Velqa_;
00094
00095
00096 bool activate,planar_,traditional_,random_points_,quadrotor_,output_files_,arm_unina_,arm_catec_;
00097 std::string path_;
00098
00099
00100 KDL::Chain chain_;
00101 KDL::JntArray jnt_pos_;
00102 KDL::Jacobian jacobian_;
00103
00104 boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00105 boost::scoped_ptr<KDL::ChainJntToJacSolver> jnt_to_jac_solver_;
00106
00113 void initZeros();
00114
00121 void base_rtw();
00122
00123
00130 void image_projection(const float& fu, const float& fv);
00131
00132
00139 void features_vector();
00140
00147 void compute_jacobian_t();
00148
00155 void compute_jacobian_u();
00156
00163 void K_control();
00164
00171 void q_control();
00172
00179 void qa_control();
00180
00187 void v_null_space_unina();
00188
00195 void qa_kinematics();
00196
00203 void v_null_space_catec();
00204
00210 Eigen::MatrixXf calcPinv(const Eigen::MatrixXf &a);
00211
00217 void pseudo_inverse(const Eigen::MatrixXf& M, const Eigen::MatrixXf& Y, Eigen::MatrixXf& X);
00218
00224 Eigen::Matrix4f GetTransform(const KDL::Frame &f);
00225
00226
00227 public:
00234 typedef iri_uncalibvs_sim::Uncalibvs_simConfig Config;
00235
00236
00243 Config config_;
00244
00253 Uncalibvs_simAlgorithm(void);
00254
00255
00261 void lock(void) { alg_mutex_.enter(); };
00262
00268 void unlock(void) { alg_mutex_.exit(); };
00269
00277 bool try_enter(void) { return alg_mutex_.try_enter(); };
00278
00290 void config_update(Config& new_cfg, uint32_t level=0);
00291
00292
00293
00294
00301 ~Uncalibvs_simAlgorithm(void);
00302
00309 void uncalib_vs_sim(const bool& traditional, const bool& random_points, const bool& quadrotor, const bool& arm_unina, const bool& arm_catec, const bool& output_files, const std::string& path, const double& lambda, const Eigen::MatrixXf& lambda_robot, const double& final_z, const Eigen::Matrix4f& cTo, const double& secs, const Eigen::MatrixXf& V2, KDL::Chain& chain, Eigen::MatrixXf& QQ, const Eigen::Matrix3f& Rquad_inertial, Eigen::MatrixXf& Vel_quad);
00310
00311 };
00312
00313 #endif