RobotAlgos.cpp

Go to the documentation of this file.
00001 /***************************************************************************
00002  *   Copyright (c) Jürgen Riegel          (juergen.riegel@web.de) 2002     *
00003  *                                                                         *
00004  *   This file is part of the FreeCAD CAx development system.              *
00005  *                                                                         *
00006  *   This library is free software; you can redistribute it and/or         *
00007  *   modify it under the terms of the GNU Library General Public           *
00008  *   License as published by the Free Software Foundation; either          *
00009  *   version 2 of the License, or (at your option) any later version.      *
00010  *                                                                         *
00011  *   This library  is distributed in the hope that it will be useful,      *
00012  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00013  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
00014  *   GNU Library General Public License for more details.                  *
00015  *                                                                         *
00016  *   You should have received a copy of the GNU Library General Public     *
00017  *   License along with this library; see the file COPYING.LIB. If not,    *
00018  *   write to the Free Software Foundation, Inc., 59 Temple Place,         *
00019  *   Suite 330, Boston, MA  02111-1307, USA                                *
00020  *                                                                         *
00021  ***************************************************************************/
00022 
00023 
00024 #include "PreCompiled.h"
00025 
00026 #ifndef _PreComp_
00027 
00028 #endif
00029 
00030 #include "kdl_cp/chain.hpp"
00031 #include "kdl_cp/chainfksolver.hpp"
00032 #include "kdl_cp/chainfksolverpos_recursive.hpp"
00033 #include "kdl_cp/frames_io.hpp"
00034 #include "kdl_cp/chainiksolver.hpp"
00035 #include "kdl_cp/chainiksolvervel_pinv.hpp"
00036 #include "kdl_cp/chainjnttojacsolver.hpp"
00037 #include "kdl_cp/chainiksolverpos_nr.hpp"
00038 
00039 #include <stdio.h>
00040 #include <iostream>
00041 
00042 #include <Base/Console.h>
00043 #include <Base/VectorPy.h>
00044 
00045 
00046 #include "RobotAlgos.h"
00047 
00048 using namespace Robot;
00049 using namespace std;
00050 using namespace KDL;
00051 
00052 #ifndef M_PI
00053     #define M_PI 3.14159265358979323846
00054     #define M_PI    3.14159265358979323846 /* pi */
00055 #endif
00056 
00057 #ifndef M_PI_2
00058     #define M_PI_2  1.57079632679489661923 /* pi/2 */
00059 #endif
00060 
00061 //===========================================================================
00062 // FeatureView
00063 //===========================================================================
00064 
00065 
00066 
00067 RobotAlgos::RobotAlgos(void) 
00068 {
00069         
00070 }
00071 
00072 RobotAlgos::~RobotAlgos()
00073 {
00074 }
00075 
00076 void RobotAlgos::Test(void)
00077 {
00078             //Definition of a kinematic chain & add segments to the chain
00079     KDL::Chain chain;
00080     chain.addSegment(Segment(Joint(Joint::RotZ),Frame(Vector(0.0,0.0,1.020))));
00081     chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.480))));
00082     chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.645))));
00083     chain.addSegment(Segment(Joint(Joint::RotZ)));
00084     chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,0.120))));
00085     chain.addSegment(Segment(Joint(Joint::RotZ)));
00086  
00087     // Create solver based on kinematic chain
00088     ChainFkSolverPos_recursive fksolver = ChainFkSolverPos_recursive(chain);
00089  
00090     // Create joint array
00091     unsigned int nj = chain.getNrOfJoints();
00092     KDL::JntArray jointpositions = JntArray(nj);
00093  
00094     // Assign some values to the joint positions
00095     for(unsigned int i=0;i<nj;i++){
00096         float myinput;
00097         printf ("Enter the position of joint %i: ",i);
00098         scanf ("%e",&myinput);
00099         jointpositions(i)=(double)myinput;
00100     }
00101  
00102     // Create the frame that will contain the results
00103     KDL::Frame cartpos;    
00104  
00105     // Calculate forward position kinematics
00106     int kinematics_status;
00107     kinematics_status = fksolver.JntToCart(jointpositions,cartpos);
00108     if(kinematics_status>=0){
00109         std::cout << cartpos <<std::endl;
00110         printf("%s \n","Succes, thanks KDL!");
00111     }else{
00112         printf("%s \n","Error: could not calculate forward kinematics :(");
00113     }
00114 
00115 
00116         //Creation of the solvers:
00117         ChainFkSolverPos_recursive fksolver1(chain);//Forward position solver
00118         ChainIkSolverVel_pinv iksolver1v(chain);//Inverse velocity solver
00119         ChainIkSolverPos_NR iksolver1(chain,fksolver1,iksolver1v,100,1e-6);//Maximum 100 iterations, stop at accuracy 1e-6
00120          
00121         //Creation of jntarrays:
00122         JntArray result(chain.getNrOfJoints());
00123         JntArray q_init(chain.getNrOfJoints());
00124          
00125         //Set destination frame
00126         Frame F_dest=cartpos;
00127          
00128         iksolver1.CartToJnt(q_init,F_dest,result);
00129 
00130         for(unsigned int i=0;i<nj;i++){
00131         printf ("Axle %i: %f \n",i,result(i));
00132     }
00133 
00134 
00135 }

Generated on Wed Nov 23 19:00:36 2011 for FreeCAD by  doxygen 1.6.1