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_alg_h_
00026 #define _uncalibvs_alg_h_
00027
00028 #include <iri_uncalibvs/UncalibvsConfig.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 #include <Eigen/Dense>
00038 #include <Eigen/Eigenvalues>
00039
00040 #include <iostream>
00041 #include <fstream>
00042 #include <stdio.h>
00043
00044 #include <geometry_msgs/Twist.h>
00045 #include <sensor_msgs/JointState.h>
00046 #include <eigen_conversions/eigen_kdl.h>
00047
00048 #include <kdl/frames.hpp>
00049 #include <kdl/frames_io.hpp>
00050 #include <kdl/chain.hpp>
00051 #include <kdl/chainfksolver.hpp>
00052 #include <kdl/chainfksolverpos_recursive.hpp>
00053 #include <kdl/chainiksolver.hpp>
00054 #include <kdl/chainiksolverpos_nr.hpp>
00055 #include <kdl/chainiksolvervel_wdls.hpp>
00056 #include <kdl/frames_io.hpp>
00057
00058 #include <boost/scoped_ptr.hpp>
00059
00066 class Uncalibvs_Algorithm
00067 {
00068 protected:
00075 CMutex alg_mutex_;
00076
00077
00078
00079 int n_,noise_;
00080 double lambda_,secs_,final_z_;
00081 float ff_,ff_old_,u0_,v0_;
00082
00083 Eigen::Matrix3f Rquad_inertial_;
00084 Eigen::Matrix4f T0c_new_,Tc0_,cTo_,T0c_0_,T0c_x_,diTj_int_,V_mod_;
00085 Eigen::MatrixXf pj_,pn_,P0_,alfas_,uv_,s_,S_,S_x_,cj_0_,cP_,cP_x_,ccP_,J_,diff_,V2_,Vel_,Vqa0_,QQ_,Jqa_,Velqa_;
00086
00087
00088 bool activate,planar_,traditional_,random_points_,quadrotor_,output_files_,arm_;
00089 std::string path_;
00090
00091
00092
00093 KDL::Chain chain_;
00094 KDL::JntArray jnt_pos_;
00095 KDL::Jacobian jacobian_;
00096
00097 boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00098 boost::scoped_ptr<KDL::ChainJntToJacSolver> jnt_to_jac_solver_;
00099
00106 void initZeros();
00107
00114 void base_rtw();
00115
00116
00123 void image_projection(const float& fu, const float& fv);
00124
00125
00132 void features_vector();
00133
00140 void compute_jacobian_t();
00141
00148 void compute_jacobian_u();
00149
00156 void K_control();
00157
00164 void q_control();
00165
00172 void qa_control();
00173
00180 void v_null_space();
00181
00188 void qa_kinematics();
00189
00190 public:
00197 typedef iri_uncalibvs::UncalibvsConfig Config;
00198
00199
00206 Config config_;
00207
00216 Uncalibvs_Algorithm(void);
00217
00218
00224 void lock(void) { alg_mutex_.enter(); };
00225
00231 void unlock(void) { alg_mutex_.exit(); };
00232
00240 bool try_enter(void) { return alg_mutex_.try_enter(); };
00241
00253 void config_update(Config& new_cfg, uint32_t level=0);
00254
00255
00256
00257
00264 ~Uncalibvs_Algorithm(void);
00265
00272 void uncalib_vs(const bool& traditional, const bool& random_points, const bool& quadrotor, const bool& arm, const bool& output_files, const std::string& path, const double& lambda, 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);
00273
00274 };
00275
00276 #endif