├── CAlgoAbstract.h ├── CAlgoFactory.cpp ├── CAlgoFactory.h ├── CConfigLoader.cpp ├── CConfigLoader.h ├── CDumpedLeastSquares.cpp ├── CDumpedLeastSquares.h ├── CJacobian.cpp ├── CJacobian.h ├── CJacobianPseudoInverse.cpp ├── CJacobianPseudoInverse.h ├── CJacobianTranspose.cpp ├── CJacobianTranspose.h ├── CJoint.cpp ├── CJoint.h ├── CLineFactory.cpp ├── CLineFactory.h ├── CLink.cpp ├── CLink.h ├── CMatrixFactory.cpp ├── CMatrixFactory.h ├── CRobot.cpp ├── CRobot.h ├── Example └── robot.xml ├── JacobianTypes.h ├── README ├── RobotTypes.h ├── SharedTypes.h ├── config.h ├── contrib └── foreach.hpp ├── lexer.cpp ├── lexer.h ├── robotdesc.sln ├── robotdesc.vcproj ├── sigslot.h ├── src ├── pugiconfig.hpp ├── pugixml.cpp └── pugixml.hpp └── testApp.cpp /CAlgoAbstract.h: -------------------------------------------------------------------------------- 1 | #ifndef __CALGOABSTRACT__ 2 | #define __CALGOABSTRACT__ 3 | 4 | #include "SharedTypes.h" 5 | #include "RobotTypes.h" 6 | #include "CRobot.h" 7 | 8 | enum AlgType 9 | { 10 | JACOBIANTRANSPOSE, 11 | JACOBIANPSEVDOINVERSE, 12 | DUMPEDLEASTSQUARES, 13 | SELECTIVEDUMPEDLEASTSQUARES, 14 | CCD 15 | }; 16 | 17 | //Abstarct class for all algorithm 18 | class CAlgoAbstract 19 | { 20 | public: 21 | CAlgoAbstract(){} 22 | virtual ~CAlgoAbstract(){} 23 | virtual OUT VectorXf CalculateData() = 0; 24 | virtual void SetAdditionalParametr(IN float & add_in) = 0; 25 | }; 26 | 27 | #endif -------------------------------------------------------------------------------- /CAlgoFactory.cpp: -------------------------------------------------------------------------------- 1 | #include "CAlgoFactory.h" 2 | #include "CJacobianTranspose.h" 3 | #include "CJacobianPseudoInverse.h" 4 | #include "CDumpedLeastSquares.h" 5 | 6 | CAlgoAbstract * CAlgoFactory::GiveMeSolver( 7 | IN AlgType atype, 8 | IN VectorXf & desired_position , 9 | IN CRobot & ptrRobot 10 | ) 11 | { 12 | CAlgoAbstract * ptr = NULL; 13 | 14 | switch(atype) 15 | { 16 | case JACOBIANTRANSPOSE: 17 | ptr = new CJacobianTranspose(desired_position , ptrRobot); 18 | break; 19 | case JACOBIANPSEVDOINVERSE: 20 | ptr = new CJacobianPseudoInverse(desired_position , ptrRobot); 21 | break; 22 | case DUMPEDLEASTSQUARES: 23 | ptr = new CDumpedLeastSquares(desired_position , ptrRobot); 24 | break; 25 | case SELECTIVEDUMPEDLEASTSQUARES: 26 | //TODO 27 | break; 28 | } 29 | 30 | return ptr; 31 | } -------------------------------------------------------------------------------- /CAlgoFactory.h: -------------------------------------------------------------------------------- 1 | #ifndef __CALGOFACTORY__ 2 | #define __CALGOFACTORY__ 3 | 4 | #include "CAlgoAbstract.h" 5 | #include "CRobot.h" 6 | 7 | class CAlgoFactory 8 | { 9 | public: 10 | CAlgoFactory(){} 11 | CAlgoAbstract * GiveMeSolver( 12 | IN AlgType atype, 13 | IN VectorXf & desired_position , 14 | IN CRobot & ptrRobot 15 | ); 16 | }; 17 | 18 | #endif -------------------------------------------------------------------------------- /CConfigLoader.cpp: -------------------------------------------------------------------------------- 1 | #include "CConfigLoader.h" 2 | #include 3 | #include "lexer.h" 4 | 5 | 6 | dh_table & CConfigLoader::GetTable() 7 | { 8 | return for_load; 9 | } 10 | 11 | bool CConfigLoader::LoadXml() 12 | { 13 | dh_parametrs temp_struct; 14 | 15 | std::string temp_string; 16 | std::string out_temp_string; 17 | 18 | Token tkn; 19 | 20 | temp_struct.z_joint_type = NOTSET; 21 | 22 | pugi::xml_document doc; 23 | pugi::xml_parse_result result = doc.load_file(fname.c_str()); 24 | //Show robot name 25 | #ifdef DEBUGOUTPUTFORXML 26 | std::cout << "Load result: " << result.description() < 7 | 8 | class CConfigLoader 9 | { 10 | std::string fname; 11 | dh_table for_load; 12 | public: 13 | CConfigLoader(std::string & xml_name):fname(xml_name){} 14 | bool LoadXml(); 15 | OUT dh_table & GetTable(); 16 | }; 17 | 18 | #endif -------------------------------------------------------------------------------- /CDumpedLeastSquares.cpp: -------------------------------------------------------------------------------- 1 | #include "CDumpedLeastSquares.h" 2 | #include "CJacobian.h" 3 | #include 4 | 5 | CDumpedLeastSquares::CDumpedLeastSquares( IN VectorXf & desired_position , IN CRobot & robot ): 6 | mtxinstance(CMatrixFactory::GetInstance()), 7 | _desired_position(desired_position), 8 | _robot(robot) 9 | { 10 | current_position.resize(6); 11 | } 12 | 13 | OUT VectorXf CDumpedLeastSquares::CalculateData() 14 | { 15 | //Result vector 16 | VectorXf delta_theta(_robot.GiveMeMatrixHolder().size()); 17 | //Vector for delta moving in space 18 | VectorXf delta_translation(6); 19 | 20 | VectorXf _temp = _desired_position; 21 | 22 | CJacobian * jac = CJacobian::GetInstance(); 23 | //TODO 24 | //should be a parameter of function 25 | //Desired accuracy 26 | float epsilon = 0.1f; 27 | 28 | for (;;) 29 | { 30 | jac->CalculateJacobian(_robot.GiveMeMatrixHolder(),_robot.GiveMeJoints(),_robot.GiveMeFullHM()); 31 | //calculation delta 32 | current_position << _robot.GiveMeFullHM()(0,3) , //X 33 | _robot.GiveMeFullHM()(1,3) , //Y 34 | _robot.GiveMeFullHM()(2,3) , //Z 35 | 0.0f, //Orientation 36 | 0.0f, //Orientation 37 | 0.0f; //Orientation 38 | 39 | #ifdef JACOBIANDEBUGOUTPUT 40 | std::cout<<"Current position"<GetJacobian(); 61 | MatrixXf two = one * jac->GetJacobian().transpose(); 62 | MatrixXf id = MatrixXf::Identity(two.rows() , two.cols()); 63 | id = (nu*nu) * id; 64 | 65 | MatrixXf result = two + id ; 66 | MatrixXf result_out; 67 | 68 | JacobiSVD svd; 69 | svd.compute(result , Eigen::ComputeThinU | Eigen::ComputeThinV); 70 | svd.pinv(result_out); 71 | 72 | #ifdef JACOBIANDEBUGOUTPUT 73 | std::cout<<"Result"<GetJacobian().transpose() * result_out; 77 | 78 | delta_theta = result_out * delta_translation; 79 | 80 | #ifdef JACOBIANDEBUGOUTPUT 81 | std::cout<<"Delta theta"< 3 | #include "config.h" 4 | 5 | CJacobian::CJacobian() : mtxf(CMatrixFactory::GetInstance()) 6 | {} 7 | 8 | void CJacobian::SetJacobianConfiguration( unsigned int row , unsigned int col ) 9 | { 10 | //We don't know configuration 11 | _jacobian.resize(row , col); 12 | } 13 | 14 | MatrixXf & CJacobian::GetJacobian() 15 | { 16 | //Get calculated Jacobian 17 | return _jacobian; 18 | } 19 | 20 | // Transformation matrix representation 21 | // 22 | //|r11 r12 r13 d14| 23 | //|r21 r22 r23 d24| 24 | //|r31 r32 r33 d34| 25 | //| 0 0 0 1| 26 | // 27 | 28 | /************************************************************************/ 29 | /* Main routine for J calculation */ 30 | /************************************************************************/ 31 | void CJacobian::CalculateJacobian( HomMatrixHolder & hom_matrix_handler , JointHandler & jhandler , IN Matrix4f & full) 32 | { 33 | unsigned int col_num = jhandler.size(); 34 | 35 | if (!col_num) 36 | { 37 | //Zero size not allowed 38 | return; 39 | } 40 | 41 | unsigned int row_num = NUMBEROFSETPARAMETERS; 42 | 43 | //Set J confiruration 44 | SetJacobianConfiguration(row_num , col_num); 45 | 46 | for (unsigned int i = 1 ; i < col_num + 1 ; ++i) 47 | { 48 | CalculateColumnOfJacobian_New(hom_matrix_handler,DHINDEX(i),jhandler[DHINDEX(i)].GetJointType(),full); 49 | } 50 | } 51 | 52 | CJacobian * CJacobian::_instance = NULL; 53 | 54 | CJacobian * CJacobian::GetInstance() 55 | { 56 | if (!_instance) 57 | _instance = new CJacobian(); 58 | 59 | return _instance; 60 | } 61 | 62 | OUT MatrixXf CJacobian::PsevdoInverse() 63 | { 64 | MatrixXf inv; 65 | JacobiSVD svd; 66 | svd.compute(_jacobian , Eigen::ComputeThinU | Eigen::ComputeThinV); 67 | svd.pinv(inv); 68 | return inv; 69 | } 70 | 71 | void CJacobian::CalculateColumnOfJacobian_New( IN HomMatrixHolder & hom_matrix_handler , IN unsigned int ind , IN JointT jt , Matrix4f & fullm) 72 | { 73 | Vector3f z0(0.0f , 0.0f , 1.0f); 74 | Vector3f zi; 75 | Matrix4f transf_matrix; 76 | Matrix3f rot_m; 77 | 78 | Vector3f p_end_effector; 79 | Vector3f pi; 80 | 81 | //Position of end effector 82 | p_end_effector<< fullm(0,3), fullm(1,3), fullm(2,3); 83 | 84 | #ifdef JACOBIANDEBUGOUTPUT 85 | std::cout<<"Pe "< 4 | 5 | CJacobianPseudoInverse::CJacobianPseudoInverse( 6 | IN VectorXf & desired_position , 7 | IN CRobot & robot 8 | ): 9 | mtxinstance(CMatrixFactory::GetInstance()), 10 | _desired_position(desired_position), 11 | _robot(robot) 12 | 13 | { 14 | current_position.resize(6); 15 | } 16 | 17 | OUT VectorXf CJacobianPseudoInverse::CalculateData() 18 | { 19 | //Result vector 20 | VectorXf delta_theta(_robot.GiveMeMatrixHolder().size()); 21 | //Vector for delta moving in space 22 | VectorXf delta_translation(6); 23 | 24 | VectorXf _temp = _desired_position; 25 | 26 | CJacobian * jac = CJacobian::GetInstance(); 27 | //TODO 28 | //should be a parameter of function 29 | //Desired accuracy 30 | float epsilon = 0.1f; 31 | 32 | for (;;) 33 | { 34 | jac->CalculateJacobian(_robot.GiveMeMatrixHolder(),_robot.GiveMeJoints(),_robot.GiveMeFullHM()); 35 | //calculation delta 36 | current_position << _robot.GiveMeFullHM()(0,3) , //X 37 | _robot.GiveMeFullHM()(1,3) , //Y 38 | _robot.GiveMeFullHM()(2,3) , //Z 39 | 0.0f, //Orientation 40 | 0.0f, //Orientation 41 | 0.0f; //Orientation 42 | 43 | #ifdef JACOBIANDEBUGOUTPUT 44 | std::cout<<"Current position"<PsevdoInverse() * delta_translation; 62 | 63 | #ifdef JACOBIANDEBUGOUTPUT 64 | std::cout<<"Delta theta"< 5 | 6 | CJacobianTranspose::CJacobianTranspose( 7 | IN VectorXf & desired_position , 8 | IN CRobot & robot 9 | ): 10 | mtxinstance(CMatrixFactory::GetInstance()), 11 | _desired_position(desired_position), 12 | _robot(robot) 13 | 14 | { 15 | current_position.resize(6); 16 | } 17 | 18 | void CJacobianTranspose::SetAdditionalParametr( IN float & add_in ) 19 | { 20 | lamda_coefficent = add_in; 21 | } 22 | 23 | OUT VectorXf CJacobianTranspose::CalculateData() 24 | { 25 | //Result vector 26 | VectorXf delta_theta(_robot.GiveMeMatrixHolder().size()); 27 | //Vector for delta moving in space 28 | VectorXf delta_translation(6); 29 | 30 | VectorXf _temp = _desired_position; 31 | 32 | CJacobian * jac = CJacobian::GetInstance(); 33 | //TODO 34 | //should be a parameter of function 35 | //Desired accuracy 36 | float epsilon = 0.1f; 37 | 38 | for (;;) 39 | { 40 | jac->CalculateJacobian(_robot.GiveMeMatrixHolder(),_robot.GiveMeJoints(),_robot.GiveMeFullHM()); 41 | //calculation delta 42 | current_position << _robot.GiveMeFullHM()(0,3) , //X 43 | _robot.GiveMeFullHM()(1,3) , //Y 44 | _robot.GiveMeFullHM()(2,3) , //Y 45 | 0.0f, 46 | 0.0f, 47 | 0.0f; 48 | 49 | delta_translation = _desired_position - current_position; 50 | #ifdef JACOBIANDEBUGOUTPUT 51 | std::cout<<"Current position"<GetJacobian().transpose(); 67 | 68 | VectorXf upper = jac->GetJacobian() * _jac_tr * delta_translation; 69 | VectorXf double_upper = upper; 70 | float one = delta_translation.dot(upper); 71 | float down = upper.dot(double_upper); 72 | 73 | lamda_coefficent = one/down; 74 | 75 | 76 | delta_theta = lamda_coefficent*jac->GetJacobian().transpose() * delta_translation; 77 | 78 | #ifdef JACOBIANDEBUGOUTPUT 79 | std::cout<<"Delta theta"< 6 | 7 | class CJoint 8 | { 9 | std::string joint_name; 10 | 11 | /************************************************************************/ 12 | /* Origin of reference frame */ 13 | /************************************************************************/ 14 | 15 | Vector3f global_joint_origin; 16 | 17 | Vector3f x_axis_unit_point; 18 | Vector3f y_axis_unit_point; 19 | Vector3f z_axis_unit_point; 20 | 21 | /************************************************************************/ 22 | /* DH parametrs */ 23 | /************************************************************************/ 24 | 25 | float d; 26 | float theta; 27 | 28 | /************************************************************************/ 29 | /* Joint type */ 30 | /************************************************************************/ 31 | 32 | JointT current_joint_type; 33 | 34 | public: 35 | 36 | CJoint(float d_in , float theta_in , JointT jt_in , std::string jname = "unnamed"); 37 | 38 | void RotateJoint(IN const float & rot_angle); 39 | void TranlsateJoint(IN float & displacement); 40 | OUT JointT GetJointType() {return current_joint_type;} 41 | OUT float GiveMeVariableParametr(); 42 | 43 | OUT float & GetDisplasmentParametr_d(){return d;} 44 | OUT float & GetRotationParametr_theta(){return theta;} 45 | 46 | OUT std::string & GetJointName(){return joint_name;} 47 | void SetGlobalPosition(IN const Vector3f & vec); 48 | }; 49 | 50 | #endif -------------------------------------------------------------------------------- /CLineFactory.cpp: -------------------------------------------------------------------------------- 1 | #include "CLineFactory.h" 2 | #include 3 | 4 | void CLine3D::FillTraectory( IN vector_storage & in_vec ) 5 | { 6 | traectory = in_vec; 7 | } 8 | 9 | 10 | //Ax + By + Cz + D = 0 - equation for line in 3d 11 | 12 | Vector3f CLine3D::GetNextPoint( IN const Vector3f & point_end , IN const Vector3f & point_start, IN const float & displacement ) 13 | { 14 | Vector3f next_point; 15 | float nu = 0; 16 | 17 | float r1 = point_end[0] - point_start[0]; 18 | float r2 = point_end[1] - point_start[1]; 19 | float r3 = point_end[2] - point_start[2]; 20 | 21 | //calculate length of vector 22 | float vec_length = sqrt(r1*r1 + r2*r2 + r3*r3); 23 | //get number of points with such displacement 24 | unsigned int number_of_points = (unsigned int)(vec_length/displacement); 25 | 26 | if(number_of_points == 1) 27 | //TODO check it. maybe i am wrong 28 | //This is point i-1, where i - last point. So next point is point end. 29 | return point_end; 30 | else 31 | nu = static_cast(1.0f/(number_of_points-1)); 32 | //Calculate next point 33 | float x_new = FMACRO(point_start[0] , point_end[0]); 34 | float y_new = FMACRO(point_start[1] , point_end[1]); 35 | float z_new = FMACRO(point_start[2] , point_end[2]); 36 | //Fill vector 37 | next_point << x_new , //x 38 | y_new , //y 39 | z_new ; //z 40 | 41 | return next_point; 42 | } -------------------------------------------------------------------------------- /CLineFactory.h: -------------------------------------------------------------------------------- 1 | #ifndef __CLINEFACTORY__ 2 | #define __CLINEFACTORY__ 3 | 4 | #include 5 | #include 6 | #include "SharedTypes.h" 7 | 8 | using namespace Eigen; 9 | 10 | class CLine3D 11 | { 12 | vector_storage traectory; 13 | public: 14 | CLine3D(){} 15 | 16 | Vector3f GetNextPoint( 17 | IN const Vector3f & point_end , 18 | IN const Vector3f & point_start, 19 | IN const float & displacement 20 | ); 21 | 22 | void FillTraectory( 23 | IN vector_storage & in_vec 24 | ); 25 | }; 26 | 27 | #endif -------------------------------------------------------------------------------- /CLink.cpp: -------------------------------------------------------------------------------- 1 | #include "CLink.h" 2 | 3 | CLink::CLink( float a_in , float alpha_in ):a(a_in),alpha(alpha_in) 4 | {} -------------------------------------------------------------------------------- /CLink.h: -------------------------------------------------------------------------------- 1 | #ifndef __CLINK__ 2 | #define __CLINK__ 3 | 4 | #include "SharedTypes.h" 5 | 6 | class CLink 7 | { 8 | Vector3f global_link_origin; 9 | 10 | /************************************************************************/ 11 | /* DH parametrs */ 12 | /************************************************************************/ 13 | float a; 14 | float alpha; 15 | 16 | //TODO : add mass center 17 | 18 | public: 19 | CLink(float a_in , float alpha_in); 20 | 21 | OUT float GetCommonNormalParametr_a(){return a;} 22 | OUT float GetZAxisRotationParametr_aplha(){return alpha;} 23 | }; 24 | 25 | #endif -------------------------------------------------------------------------------- /CMatrixFactory.cpp: -------------------------------------------------------------------------------- 1 | #include "CMatrixFactory.h" 2 | #include 3 | 4 | Matrix4f CMatrixFactory::CalculateHTranslationMatrix( 5 | float alpha, 6 | float a, 7 | float d, 8 | float theta 9 | ) 10 | { 11 | Matrix4f mat_tr; 12 | 13 | //First row 14 | float r11 = 15 | static_cast(cos(CONVERT_TO_RAD(theta))); 16 | float r12 = 17 | static_cast( 18 | -sin(CONVERT_TO_RAD(theta))*cos(CONVERT_TO_RAD(alpha)) 19 | ); 20 | float r13 = 21 | static_cast( 22 | sin(CONVERT_TO_RAD(theta))*sin(CONVERT_TO_RAD(alpha)) 23 | ); 24 | float r14 = 25 | static_cast( 26 | a*cos(CONVERT_TO_RAD(theta)) 27 | ); 28 | //Second row 29 | float r21 = 30 | static_cast( 31 | sin(CONVERT_TO_RAD(theta)) 32 | ); 33 | float r22 = 34 | static_cast( 35 | cos(CONVERT_TO_RAD(theta))*cos(CONVERT_TO_RAD(alpha)) 36 | ); 37 | float r23 = 38 | static_cast( 39 | -cos(CONVERT_TO_RAD(theta))*sin(CONVERT_TO_RAD(alpha)) 40 | ); 41 | float r24 = 42 | static_cast( 43 | a*sin(CONVERT_TO_RAD(theta)) 44 | ); 45 | //Third row 46 | float r31 = 0.0f; 47 | float r32 = 48 | static_cast( 49 | sin(CONVERT_TO_RAD(alpha)) 50 | ); 51 | float r33 = 52 | static_cast( 53 | cos(CONVERT_TO_RAD(alpha)) 54 | ); 55 | float r34 = d; 56 | //Forth row 57 | float r41 = 0.0f; 58 | float r42 = 0.0f;; 59 | float r43 = 0.0f;; 60 | float r44 = 1.0f;; 61 | 62 | mat_tr << r11 , r12 , r13 , r14 , 63 | r21 , r22 , r23 , r24 , 64 | r31 , r32 , r33 , r34 , 65 | r41 , r42 , r43 , r44 ; 66 | 67 | return mat_tr; 68 | } 69 | 70 | CMatrixFactory * CMatrixFactory::_instance = NULL; 71 | 72 | CMatrixFactory * CMatrixFactory::GetInstance() 73 | { 74 | if(!_instance) 75 | _instance = new CMatrixFactory(); 76 | 77 | return _instance; 78 | } 79 | 80 | Matrix4f CMatrixFactory::CreateRotationMatrixAroundZ( float alpha ) 81 | { 82 | Matrix4f _temp; 83 | 84 | //First row 85 | float r11 = static_cast( 86 | cos(CONVERT_TO_RAD(alpha)) 87 | ); 88 | float r12 = static_cast( 89 | -sin(CONVERT_TO_RAD(alpha)) 90 | ); 91 | float r13 = 0.0f; 92 | float r14 = 0.0f; 93 | //Second row 94 | float r21 = static_cast( 95 | sin(CONVERT_TO_RAD(alpha)) 96 | ); 97 | float r22 = static_cast( 98 | cos(CONVERT_TO_RAD(alpha)) 99 | ); 100 | float r23 = 0.0f; 101 | float r24 = 0.0f; 102 | //Third row 103 | float r31 = 0.0f; 104 | float r32 = 0.0f; 105 | float r33 = 1.0f; 106 | float r34 = 0.0f; 107 | //Forth row 108 | float r41 = 0.0f; 109 | float r42 = 0.0f; 110 | float r43 = 0.0f; 111 | float r44 = 0.0f; 112 | 113 | _temp << r11 , r12 , r13 , r14 , 114 | r21 , r22 , r23 , r24 , 115 | r31 , r32 , r33 , r34 , 116 | r41 , r42 , r43 , r44 ; 117 | 118 | return _temp; 119 | } 120 | 121 | Matrix4f CMatrixFactory::CreateRotationMatrixAroundY( float beta ) 122 | { 123 | Matrix4f _temp; 124 | 125 | //First row 126 | float r11 = static_cast( 127 | cos(CONVERT_TO_RAD(beta)) 128 | ); 129 | float r12 = 0.0f; 130 | float r13 = static_cast( 131 | sin(CONVERT_TO_RAD(beta)) 132 | ); 133 | float r14 = 0.0f; 134 | //Second row 135 | float r21 = 0.0f; 136 | float r22 = 1.0f; 137 | float r23 = 0.0f; 138 | float r24 = 0.0f; 139 | //Third row 140 | float r31 = static_cast( 141 | -sin(CONVERT_TO_RAD(beta)) 142 | ); 143 | float r32 = 0.0f; 144 | float r33 = static_cast( 145 | cos(CONVERT_TO_RAD(beta)) 146 | ); 147 | float r34 = 0.0f; 148 | //Forth row 149 | float r41 = 0.0f; 150 | float r42 = 0.0f; 151 | float r43 = 0.0f; 152 | float r44 = 0.0f; 153 | 154 | _temp << r11 , r12 , r13 , r14 , 155 | r21 , r22 , r23 , r24 , 156 | r31 , r32 , r33 , r34 , 157 | r41 , r42 , r43 , r44 ; 158 | 159 | return _temp; 160 | } 161 | 162 | Matrix4f CMatrixFactory::CreateRotationMatrixAroundX( float gamma ) 163 | { 164 | Matrix4f _temp; 165 | 166 | //First row 167 | float r11 = 1.0f; 168 | float r12 = 0.0f; 169 | float r13 = 0.0f; 170 | float r14 = 0.0f; 171 | //Second row 172 | float r21 = 0.0f; 173 | float r22 = static_cast( 174 | cos(CONVERT_TO_RAD(gamma)) 175 | ); 176 | float r23 = static_cast( 177 | -sin(CONVERT_TO_RAD(gamma)) 178 | ); 179 | float r24 = 0.0f; 180 | //Third row 181 | float r31 = 0.0f; 182 | float r32 = static_cast( 183 | sin(CONVERT_TO_RAD(gamma)) 184 | ); 185 | float r33 = static_cast( 186 | cos(CONVERT_TO_RAD(gamma)) 187 | ); 188 | float r34 = 0.0f; 189 | //Forth row 190 | float r41 = 0.0f; 191 | float r42 = 0.0f; 192 | float r43 = 0.0f; 193 | float r44 = 0.0f; 194 | 195 | _temp << r11 , r12 , r13 , r14 , 196 | r21 , r22 , r23 , r24 , 197 | r31 , r32 , r33 , r34 , 198 | r41 , r42 , r43 , r44 ; 199 | 200 | return _temp; 201 | } 202 | 203 | Matrix4f CMatrixFactory::CreateTranslateMatrixX( float dx ) 204 | { 205 | Matrix4f _temp = Matrix4f::Identity(); 206 | 207 | _temp(0,3) = dx; 208 | 209 | return _temp; 210 | } 211 | 212 | Matrix4f CMatrixFactory::CreateTranslateMatrixY( float dy ) 213 | { 214 | Matrix4f _temp = Matrix4f::Identity(); 215 | 216 | _temp(1,3) = dy; 217 | 218 | return _temp; 219 | } 220 | 221 | Matrix4f CMatrixFactory::CreateTranslateMatrixZ( float dz ) 222 | { 223 | Matrix4f _temp = Matrix4f::Identity(); 224 | 225 | _temp(2,3) = dz; 226 | 227 | return _temp; 228 | } 229 | 230 | Matrix3f CMatrixFactory::ExtractRotationMatrix( Matrix4f & hm ) 231 | { 232 | return hm.block(0,0,3,3); 233 | } 234 | 235 | Vector3f CMatrixFactory::ExtractTranslationVector( Matrix4f & hm ) 236 | { 237 | Vector3f vec; 238 | 239 | vec(0) = hm(0,3); 240 | vec(1) = hm(1,3); 241 | vec(2) = hm(2,3); 242 | 243 | return vec; 244 | } 245 | 246 | Vector3f CMatrixFactory::MultiplyVectors( Vector3f & vec_one , Vector3f & vec_two ) 247 | { 248 | Vector3f vec_res; 249 | //Equation [A,B] = (Ay*Bz - Az*By , AzBx - Ax*Bz , AxBy - AyBx) 250 | vec_res(0) = vec_one(1)*vec_two(2) - vec_one(2)*vec_two(1); 251 | vec_res(1) = vec_one(2)*vec_two(0) - vec_one(0)*vec_two(2); 252 | vec_res(2) = vec_one(0)*vec_two(1) - vec_one(1)*vec_two(0); 253 | 254 | #ifdef JACOBIANDEBUGOUTPUT 255 | std::cout<<"k*d"<( 264 | sqrt(invec(0)*invec(0) + invec(1)*invec(1) + invec(2)*invec(2)) 265 | ); 266 | 267 | return res; 268 | } 269 | 270 | 271 | -------------------------------------------------------------------------------- /CMatrixFactory.h: -------------------------------------------------------------------------------- 1 | #ifndef __CMATRIXFACTORY__ 2 | #define __CMATRIXFACTORY__ 3 | 4 | /************************************************************************/ 5 | /* CMatrixFactory */ 6 | /************************************************************************/ 7 | 8 | #include "SharedTypes.h" 9 | 10 | #define PI 3.14159265 11 | #define CONVERT_TO_RAD(x) x*(PI/180) 12 | 13 | class CMatrixFactory 14 | { 15 | CMatrixFactory() {} 16 | 17 | static CMatrixFactory * _instance; 18 | 19 | public: 20 | 21 | /************************************************************************/ 22 | /* Rotation matrix */ 23 | /************************************************************************/ 24 | 25 | OUT Matrix4f CreateRotationMatrixAroundZ( IN float alpha ); 26 | OUT Matrix4f CreateRotationMatrixAroundY( IN float beta ); 27 | OUT Matrix4f CreateRotationMatrixAroundX( IN float gamma ); 28 | 29 | 30 | /************************************************************************/ 31 | /* Translation matrix */ 32 | /************************************************************************/ 33 | 34 | OUT Matrix4f CreateTranslateMatrixX( IN float dx ); 35 | OUT Matrix4f CreateTranslateMatrixY( IN float dy ); 36 | OUT Matrix4f CreateTranslateMatrixZ( IN float dz ); 37 | 38 | /************************************************************************/ 39 | /* Transformation matrix from frame i to i-1 */ 40 | /************************************************************************/ 41 | 42 | OUT Matrix4f CalculateHTranslationMatrix( 43 | IN float alpha, 44 | IN float a, 45 | IN float d, 46 | IN float theta 47 | ); 48 | /************************************************************************/ 49 | /* Help functions */ 50 | /************************************************************************/ 51 | OUT Matrix3f ExtractRotationMatrix( IN Matrix4f & hm ); 52 | OUT Vector3f ExtractTranslationVector ( IN Matrix4f & hm ); 53 | OUT Vector3f MultiplyVectors(IN Vector3f & vec_one , IN Vector3f & vec_two); 54 | OUT float GetLengthOfVector(IN VectorXf & invec); 55 | /************************************************************************/ 56 | /* Full calculation algo */ 57 | /************************************************************************/ 58 | 59 | 60 | static CMatrixFactory * GetInstance(); 61 | 62 | }; 63 | 64 | #endif -------------------------------------------------------------------------------- /CRobot.cpp: -------------------------------------------------------------------------------- 1 | #include "CRobot.h" 2 | #include "CMatrixFactory.h" 3 | #include 4 | 5 | bool CRobot::LoadConfig( const dh_table & tbl ) 6 | { 7 | unsigned int sz = tbl.size(); 8 | if(!sz) return false; 9 | 10 | robot_dh = tbl; 11 | 12 | for (unsigned int i = 0 ; i < sz ; ++i) 13 | { 14 | //Saving joint data to robot 15 | jhandle.push_back(CJoint(robot_dh[i].d,robot_dh[i].theta,robot_dh[i].z_joint_type,robot_dh[i].joint_name)); 16 | //Saving link data to robot 17 | linkhadle.push_back(CLink(robot_dh[i].a,robot_dh[i].alpha)); 18 | //Calculating h_matrix and saving to robot 19 | hmtx.push_back( 20 | matrix_algo->CalculateHTranslationMatrix( 21 | linkhadle[i].GetZAxisRotationParametr_aplha(), 22 | linkhadle[i].GetCommonNormalParametr_a(), 23 | jhandle[i].GetDisplasmentParametr_d(), 24 | jhandle[i].GetRotationParametr_theta() 25 | ) 26 | ); 27 | } 28 | 29 | CaclulateFullTransormationMatrix(); 30 | 31 | return true; 32 | } 33 | 34 | CRobot::CRobot( Vector3f & vec ) : zero_origin(vec) , matrix_algo(CMatrixFactory::GetInstance()) , number_of_var_parameters(0) 35 | {} 36 | 37 | void CRobot::SetOrigin( Vector3f & newOrigin ) 38 | { 39 | zero_origin = newOrigin; 40 | } 41 | 42 | bool CRobot::RotateJoint( unsigned int ind , float angle ) 43 | { 44 | if (ind > jhandle.size()) 45 | { 46 | //Bad index 47 | return false; 48 | } 49 | CJoint & current_joint = jhandle[ind]; 50 | 51 | if (current_joint.GetJointType() != REVOLUTE) 52 | { 53 | //We can rotate only revolute joint 54 | return false; 55 | } 56 | //TODO 57 | //add signal for this peace of code 58 | current_joint.RotateJoint(angle); 59 | //Recalculate HM for specified joint 60 | CalculateJoint(ind); 61 | 62 | return true; 63 | } 64 | 65 | bool CRobot::TranslateJoint( unsigned int ind , float displasment ) 66 | { 67 | if (ind > jhandle.size()) 68 | { 69 | //Bad index 70 | return false; 71 | } 72 | CJoint & current_joint = jhandle[ind]; 73 | //We can translate only prismatic joint 74 | if (current_joint.GetJointType() != PRISMATIC) 75 | { 76 | //We can translate only prismatic joint 77 | return false; 78 | } 79 | //TODO 80 | //add signal for this peace of code 81 | current_joint.TranlsateJoint(displasment); 82 | 83 | //Recalculate HM for specified joint 84 | CalculateJoint(ind); 85 | 86 | return true; 87 | } 88 | 89 | bool CRobot::PrintHomogenTransformationMatrix() 90 | { 91 | if(jhandle.size() != hmtx.size()) 92 | { 93 | //TODO 94 | //May be i should add some extra info here 95 | std::cout<<"Number of Joints doesn't match number of ham. matrix. Suppose you have got extra for end-effector"<CalculateHTranslationMatrix( 182 | linkhadle[ind].GetZAxisRotationParametr_aplha(), 183 | linkhadle[ind].GetCommonNormalParametr_a(), 184 | jhandle[ind].GetDisplasmentParametr_d(), 185 | jhandle[ind].GetRotationParametr_theta() 186 | ); 187 | 188 | CaclulateFullTransormationMatrix(); 189 | 190 | return true; 191 | } 192 | 193 | void CRobot::PrintConfiguration() 194 | { 195 | unsigned int sz = jhandle.size(); 196 | 197 | for (unsigned int i = 0 ; i < sz ; ++i) 198 | { 199 | std::cout<<"Joint name : "< 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /JacobianTypes.h: -------------------------------------------------------------------------------- 1 | #ifndef __JACOBIANTYPES__ 2 | #define __JACOBIANTYPES__ 3 | 4 | #include 5 | #include 6 | 7 | #include "SharedTypes.h" 8 | #include "RobotTypes.h" 9 | 10 | using namespace Eigen; 11 | 12 | #endif -------------------------------------------------------------------------------- /README: -------------------------------------------------------------------------------- 1 | This program loads xml that describes robot in DH parameters and able 2 | to solve IK problem. 3 | 4 | Solvers: 5 | Jacobian Transpose 6 | Jacobian Pseudoinverse 7 | DLS 8 | 9 | TODO: 10 | Add CCD solver 11 | Add SDLD solver 12 | Add path and trajectory planner -------------------------------------------------------------------------------- /RobotTypes.h: -------------------------------------------------------------------------------- 1 | #ifndef __ROBOTTYPES__ 2 | #define __ROBOTTYPES__ 3 | 4 | #include "CLink.h" 5 | #include "CJoint.h" 6 | 7 | typedef std::vector JointHandler; 8 | typedef std::vector LinkHandler; 9 | 10 | enum 11 | { 12 | //This parameter is about how many variable used for end effector 13 | //position and orientation : 3 for position, 3 for orientation 14 | NUMBEROFSETPARAMETERS = 6 15 | }; 16 | 17 | #endif -------------------------------------------------------------------------------- /SharedTypes.h: -------------------------------------------------------------------------------- 1 | #ifndef __SHAREDTYPES__ 2 | #define __SHAREDTYPES__ 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | #include 9 | #include 10 | #include "sigslot.h" 11 | 12 | using namespace Eigen; 13 | 14 | #define DHINDEX(x) x-1 15 | #define IN 16 | #define OUT 17 | #define FMACRO(axis_one , axis_two) (axis_one + nu*axis_two)/(1 + nu) 18 | 19 | enum JointT {REVOLUTE , PRISMATIC , CONSTANTJOINT , NOTSET}; 20 | enum AxisT {AxisX , AxisY , AxisZ}; 21 | 22 | struct dh_parametrs 23 | { 24 | float a; //Length of common normal 25 | float alpha; //Angle between zi and zi-1 along xi 26 | float d; //distance between xi and xi-1 along zi (variable for prismatic) 27 | float theta; //Angle between xi and xi-1 along zi (variavle for revolute) 28 | JointT z_joint_type;//Joint type at z-1 axis 29 | std::string joint_name; 30 | }; 31 | 32 | typedef std::vector dh_table; 33 | typedef std::vector > vector_storage; 34 | typedef std::vector > HomMatrixHolder; 35 | 36 | #endif -------------------------------------------------------------------------------- /config.h: -------------------------------------------------------------------------------- 1 | #ifndef __CONFIG_H_ 2 | #define __CONFIG_H_ 3 | 4 | #define SIGSLOT_PURE_ISO 5 | //#define DEBUGOUTPUTFORLEXER 6 | //#define DEBUGOUTPUTFORXML 7 | //#define JACOBIANDEBUGOUTPUT 8 | //#define CCDDEBUGOUTPUT 9 | 10 | #endif -------------------------------------------------------------------------------- /contrib/foreach.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Boost.Foreach support for pugixml classes. 3 | * This file is provided to the public domain. 4 | * Written by Arseny Kapoulkine (arseny.kapoulkine@gmail.com) 5 | */ 6 | 7 | #ifndef HEADER_PUGIXML_FOREACH_HPP 8 | #define HEADER_PUGIXML_FOREACH_HPP 9 | 10 | #include "pugixml.hpp" 11 | 12 | /* 13 | * These types add support for BOOST_FOREACH macro to xml_node and xml_document classes (child iteration only). 14 | * Example usage: 15 | * BOOST_FOREACH(xml_node n, doc) {} 16 | */ 17 | 18 | namespace boost 19 | { 20 | template struct range_mutable_iterator; 21 | template struct range_const_iterator; 22 | 23 | template<> struct range_mutable_iterator 24 | { 25 | typedef pugi::xml_node::iterator type; 26 | }; 27 | 28 | template<> struct range_const_iterator 29 | { 30 | typedef pugi::xml_node::iterator type; 31 | }; 32 | 33 | template<> struct range_mutable_iterator 34 | { 35 | typedef pugi::xml_document::iterator type; 36 | }; 37 | 38 | template<> struct range_const_iterator 39 | { 40 | typedef pugi::xml_document::iterator type; 41 | }; 42 | } 43 | 44 | /* 45 | * These types add support for BOOST_FOREACH macro to xml_node and xml_document classes (child/attribute iteration). 46 | * Example usage: 47 | * BOOST_FOREACH(xml_node n, children(doc)) {} 48 | * BOOST_FOREACH(xml_node n, attributes(doc)) {} 49 | */ 50 | 51 | namespace pugi 52 | { 53 | struct xml_node_children_adapter 54 | { 55 | typedef pugi::xml_node::iterator iterator; 56 | typedef pugi::xml_node::iterator const_iterator; 57 | 58 | xml_node node; 59 | 60 | const_iterator begin() const 61 | { 62 | return node.begin(); 63 | } 64 | 65 | const_iterator end() const 66 | { 67 | return node.end(); 68 | } 69 | }; 70 | 71 | xml_node_children_adapter children(const pugi::xml_node& node) 72 | { 73 | xml_node_children_adapter result = {node}; 74 | return result; 75 | } 76 | 77 | struct xml_node_attribute_adapter 78 | { 79 | typedef pugi::xml_node::attribute_iterator iterator; 80 | typedef pugi::xml_node::attribute_iterator const_iterator; 81 | 82 | xml_node node; 83 | 84 | const_iterator begin() const 85 | { 86 | return node.attributes_begin(); 87 | } 88 | 89 | const_iterator end() const 90 | { 91 | return node.attributes_end(); 92 | } 93 | }; 94 | 95 | xml_node_attribute_adapter attributes(const pugi::xml_node& node) 96 | { 97 | xml_node_attribute_adapter result = {node}; 98 | return result; 99 | } 100 | } 101 | 102 | #endif 103 | -------------------------------------------------------------------------------- /lexer.cpp: -------------------------------------------------------------------------------- 1 | #include "lexer.h" 2 | 3 | #ifdef _DEBUG 4 | #define dbgprintf(message,...) printf(message,__VA_ARGS__) 5 | #else 6 | #define dbgprintf(message) 7 | #endif 8 | 9 | 10 | int scan(char** p, char** lex) 11 | { 12 | char* marker; 13 | if (lex) *lex = *p; 14 | 15 | { 16 | unsigned char yych; 17 | 18 | yych = (unsigned char)**p; 19 | if (yych <= ' ') { 20 | if (yych == '\t') goto yy6; 21 | if (yych <= 0x1F) goto yy8; 22 | goto yy6; 23 | } else { 24 | if (yych <= '9') { 25 | if (yych <= '/') goto yy8; 26 | goto yy4; 27 | } else { 28 | if (yych != 'v') goto yy8; 29 | } 30 | } 31 | yych = (unsigned char)*(marker = ++*p); 32 | if (yych == 'a') goto yy16; 33 | yy3: 34 | { return END; } 35 | yy4: 36 | ++*p; 37 | if ((yych = (unsigned char)**p) == '.') goto yy11; 38 | if (yych <= '/') goto yy5; 39 | if (yych <= '9') goto yy14; 40 | yy5: 41 | { return INT; } 42 | yy6: 43 | ++*p; 44 | yych = (unsigned char)**p; 45 | goto yy10; 46 | yy7: 47 | { return SPACE; } 48 | yy8: 49 | yych = (unsigned char)*++*p; 50 | goto yy3; 51 | yy9: 52 | ++*p; 53 | yych = (unsigned char)**p; 54 | yy10: 55 | if (yych == '\t') goto yy9; 56 | if (yych == ' ') goto yy9; 57 | goto yy7; 58 | yy11: 59 | ++*p; 60 | yych = (unsigned char)**p; 61 | if (yych <= '/') goto yy13; 62 | if (yych <= '9') goto yy11; 63 | yy13: 64 | { return FLOAT; } 65 | yy14: 66 | ++*p; 67 | yych = (unsigned char)**p; 68 | if (yych == '.') goto yy11; 69 | if (yych <= '/') goto yy5; 70 | if (yych <= '9') goto yy14; 71 | goto yy5; 72 | yy16: 73 | yych = (unsigned char)*++*p; 74 | if (yych == 'r') goto yy18; 75 | yy17: 76 | *p = marker; 77 | goto yy3; 78 | yy18: 79 | yych = (unsigned char)*++*p; 80 | if (yych != '_') goto yy17; 81 | ++*p; 82 | { return VAR; } 83 | } 84 | 85 | } 86 | 87 | Token scan_string( 88 | const char * pp, 89 | unsigned int str_len, 90 | std::string & out_default_var 91 | ) 92 | { 93 | char *p = (char *)pp; 94 | char *last; 95 | int token; 96 | 97 | token = scan(&p, &last); 98 | int sz = p - last; 99 | switch (token) 100 | { 101 | case FLOAT: 102 | #ifdef DEBUGOUTPUTFORLEXER 103 | dbgprintf("FLOAT: '%.*s'\n", sz, last); 104 | #endif 105 | break; 106 | case INT : 107 | #ifdef DEBUGOUTPUTFORLEXER 108 | dbgprintf("INT: '%.*s'\n", sz, last); 109 | #endif 110 | break; 111 | case VAR : 112 | #ifdef DEBUGOUTPUTFORLEXER 113 | dbgprintf("VAR: '%.*s'\n", sz, last); 114 | #endif 115 | if(str_len==sz){ 116 | token = (int)ERROR; 117 | break; 118 | } 119 | //We should get default value 120 | token = scan(&p, &last); 121 | 122 | if(token != FLOAT && token != INT){ 123 | token = (int)ERROR; 124 | break; 125 | } 126 | 127 | sz = p - last; 128 | 129 | out_default_var = std::string(last,sz); 130 | 131 | token = (int)VAR; 132 | 133 | break; 134 | default : 135 | token = (int)ERROR; 136 | } 137 | 138 | 139 | 140 | return (Token)token; 141 | } -------------------------------------------------------------------------------- /lexer.h: -------------------------------------------------------------------------------- 1 | #ifndef __STRINGLEXER__ 2 | #define __STRINGLEXER__ 3 | 4 | #include 5 | #include 6 | 7 | #include "SharedTypes.h" 8 | #include "config.h" 9 | 10 | enum Token { 11 | INT, FLOAT, SPACE, END , VAR , ERROR 12 | }; 13 | 14 | Token scan_string( 15 | IN const char * p, 16 | IN unsigned int str_len, 17 | OUT std::string & out_default_var 18 | ); 19 | 20 | #endif -------------------------------------------------------------------------------- /robotdesc.sln: -------------------------------------------------------------------------------- 1 |  2 | Microsoft Visual Studio Solution File, Format Version 10.00 3 | # Visual Studio 2008 4 | Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "robotdesc", "robotdesc.vcproj", "{46CD5D2E-A17C-426E-B775-CC508706B49C}" 5 | EndProject 6 | Global 7 | GlobalSection(SolutionConfigurationPlatforms) = preSolution 8 | Debug|Win32 = Debug|Win32 9 | Release|Win32 = Release|Win32 10 | EndGlobalSection 11 | GlobalSection(ProjectConfigurationPlatforms) = postSolution 12 | {46CD5D2E-A17C-426E-B775-CC508706B49C}.Debug|Win32.ActiveCfg = Debug|Win32 13 | {46CD5D2E-A17C-426E-B775-CC508706B49C}.Debug|Win32.Build.0 = Debug|Win32 14 | {46CD5D2E-A17C-426E-B775-CC508706B49C}.Release|Win32.ActiveCfg = Release|Win32 15 | {46CD5D2E-A17C-426E-B775-CC508706B49C}.Release|Win32.Build.0 = Release|Win32 16 | EndGlobalSection 17 | GlobalSection(SolutionProperties) = preSolution 18 | HideSolutionNode = FALSE 19 | EndGlobalSection 20 | EndGlobal 21 | -------------------------------------------------------------------------------- /robotdesc.vcproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/kirillv/cpp-inverse-kinematics-library/7e444c0e91235ae028f8283c974591536628f331/robotdesc.vcproj -------------------------------------------------------------------------------- /sigslot.h: -------------------------------------------------------------------------------- 1 | // sigslot.h: Signal/Slot classes 2 | // 3 | // Written by Sarah Thompson (sarah@telergy.com) 2002. 4 | // 5 | // License: Public domain. You are free to use this code however you like, with the proviso that 6 | // the author takes on no responsibility or liability for any use. 7 | // 8 | // QUICK DOCUMENTATION 9 | // 10 | // (see also the full documentation at http://sigslot.sourceforge.net/) 11 | // 12 | // #define switches 13 | // SIGSLOT_PURE_ISO - Define this to force ISO C++ compliance. This also disables 14 | // all of the thread safety support on platforms where it is 15 | // available. 16 | // 17 | // SIGSLOT_USE_POSIX_THREADS - Force use of Posix threads when using a C++ compiler other than 18 | // gcc on a platform that supports Posix threads. (When using gcc, 19 | // this is the default - use SIGSLOT_PURE_ISO to disable this if 20 | // necessary) 21 | // 22 | // SIGSLOT_DEFAULT_MT_POLICY - Where thread support is enabled, this defaults to multi_threaded_global. 23 | // Otherwise, the default is single_threaded. #define this yourself to 24 | // override the default. In pure ISO mode, anything other than 25 | // single_threaded will cause a compiler error. 26 | // 27 | // PLATFORM NOTES 28 | // 29 | // Win32 - On Win32, the WIN32 symbol must be #defined. Most mainstream 30 | // compilers do this by default, but you may need to define it 31 | // yourself if your build environment is less standard. This causes 32 | // the Win32 thread support to be compiled in and used automatically. 33 | // 34 | // Unix/Linux/BSD, etc. - If you're using gcc, it is assumed that you have Posix threads 35 | // available, so they are used automatically. You can override this 36 | // (as under Windows) with the SIGSLOT_PURE_ISO switch. If you're using 37 | // something other than gcc but still want to use Posix threads, you 38 | // need to #define SIGSLOT_USE_POSIX_THREADS. 39 | // 40 | // ISO C++ - If none of the supported platforms are detected, or if 41 | // SIGSLOT_PURE_ISO is defined, all multithreading support is turned off, 42 | // along with any code that might cause a pure ISO C++ environment to 43 | // complain. Before you ask, gcc -ansi -pedantic won't compile this 44 | // library, but gcc -ansi is fine. Pedantic mode seems to throw a lot of 45 | // errors that aren't really there. If you feel like investigating this, 46 | // please contact the author. 47 | // 48 | // 49 | // THREADING MODES 50 | // 51 | // single_threaded - Your program is assumed to be single threaded from the point of view 52 | // of signal/slot usage (i.e. all objects using signals and slots are 53 | // created and destroyed from a single thread). Behaviour if objects are 54 | // destroyed concurrently is undefined (i.e. you'll get the occasional 55 | // segmentation fault/memory exception). 56 | // 57 | // multi_threaded_global - Your program is assumed to be multi threaded. Objects using signals and 58 | // slots can be safely created and destroyed from any thread, even when 59 | // connections exist. In multi_threaded_global mode, this is achieved by a 60 | // single global mutex (actually a critical section on Windows because they 61 | // are faster). This option uses less OS resources, but results in more 62 | // opportunities for contention, possibly resulting in more context switches 63 | // than are strictly necessary. 64 | // 65 | // multi_threaded_local - Behaviour in this mode is essentially the same as multi_threaded_global, 66 | // except that each signal, and each object that inherits has_slots, all 67 | // have their own mutex/critical section. In practice, this means that 68 | // mutex collisions (and hence context switches) only happen if they are 69 | // absolutely essential. However, on some platforms, creating a lot of 70 | // mutexes can slow down the whole OS, so use this option with care. 71 | // 72 | // USING THE LIBRARY 73 | // 74 | // See the full documentation at http://sigslot.sourceforge.net/ 75 | // 76 | // 77 | 78 | #ifndef SIGSLOT_H__ 79 | #define SIGSLOT_H__ 80 | 81 | #include 82 | #include 83 | #include "config.h" 84 | 85 | #if defined(SIGSLOT_PURE_ISO) || (!defined(WIN32) && !defined(__GNUG__) && !defined(SIGSLOT_USE_POSIX_THREADS)) 86 | # define _SIGSLOT_SINGLE_THREADED 87 | #elif defined(WIN32) 88 | # define _SIGSLOT_HAS_WIN32_THREADS 89 | # include 90 | #elif defined(__GNUG__) || defined(SIGSLOT_USE_POSIX_THREADS) 91 | # define _SIGSLOT_HAS_POSIX_THREADS 92 | # include 93 | #else 94 | # define _SIGSLOT_SINGLE_THREADED 95 | #endif 96 | 97 | #ifndef SIGSLOT_DEFAULT_MT_POLICY 98 | # ifdef _SIGSLOT_SINGLE_THREADED 99 | # define SIGSLOT_DEFAULT_MT_POLICY single_threaded 100 | # else 101 | # define SIGSLOT_DEFAULT_MT_POLICY multi_threaded_local 102 | # endif 103 | #endif 104 | 105 | 106 | namespace sigslot { 107 | 108 | class single_threaded 109 | { 110 | public: 111 | single_threaded() 112 | { 113 | ; 114 | } 115 | 116 | virtual ~single_threaded() 117 | { 118 | ; 119 | } 120 | 121 | virtual void lock() 122 | { 123 | ; 124 | } 125 | 126 | virtual void unlock() 127 | { 128 | ; 129 | } 130 | }; 131 | 132 | #ifdef _SIGSLOT_HAS_WIN32_THREADS 133 | // The multi threading policies only get compiled in if they are enabled. 134 | class multi_threaded_global 135 | { 136 | public: 137 | multi_threaded_global() 138 | { 139 | static bool isinitialised = false; 140 | 141 | if(!isinitialised) 142 | { 143 | InitializeCriticalSection(get_critsec()); 144 | isinitialised = true; 145 | } 146 | } 147 | 148 | multi_threaded_global(const multi_threaded_global&) 149 | { 150 | ; 151 | } 152 | 153 | virtual ~multi_threaded_global() 154 | { 155 | ; 156 | } 157 | 158 | virtual void lock() 159 | { 160 | EnterCriticalSection(get_critsec()); 161 | } 162 | 163 | virtual void unlock() 164 | { 165 | LeaveCriticalSection(get_critsec()); 166 | } 167 | 168 | private: 169 | CRITICAL_SECTION* get_critsec() 170 | { 171 | static CRITICAL_SECTION g_critsec; 172 | return &g_critsec; 173 | } 174 | }; 175 | 176 | class multi_threaded_local 177 | { 178 | public: 179 | multi_threaded_local() 180 | { 181 | InitializeCriticalSection(&m_critsec); 182 | } 183 | 184 | multi_threaded_local(const multi_threaded_local&) 185 | { 186 | InitializeCriticalSection(&m_critsec); 187 | } 188 | 189 | virtual ~multi_threaded_local() 190 | { 191 | DeleteCriticalSection(&m_critsec); 192 | } 193 | 194 | virtual void lock() 195 | { 196 | EnterCriticalSection(&m_critsec); 197 | } 198 | 199 | virtual void unlock() 200 | { 201 | LeaveCriticalSection(&m_critsec); 202 | } 203 | 204 | private: 205 | CRITICAL_SECTION m_critsec; 206 | }; 207 | #endif // _SIGSLOT_HAS_WIN32_THREADS 208 | 209 | #ifdef _SIGSLOT_HAS_POSIX_THREADS 210 | // The multi threading policies only get compiled in if they are enabled. 211 | class multi_threaded_global 212 | { 213 | public: 214 | multi_threaded_global() 215 | { 216 | pthread_mutex_init(get_mutex(), NULL); 217 | } 218 | 219 | multi_threaded_global(const multi_threaded_global&) 220 | { 221 | ; 222 | } 223 | 224 | virtual ~multi_threaded_global() 225 | { 226 | ; 227 | } 228 | 229 | virtual void lock() 230 | { 231 | pthread_mutex_lock(get_mutex()); 232 | } 233 | 234 | virtual void unlock() 235 | { 236 | pthread_mutex_unlock(get_mutex()); 237 | } 238 | 239 | private: 240 | pthread_mutex_t* get_mutex() 241 | { 242 | static pthread_mutex_t g_mutex; 243 | return &g_mutex; 244 | } 245 | }; 246 | 247 | class multi_threaded_local 248 | { 249 | public: 250 | multi_threaded_local() 251 | { 252 | pthread_mutex_init(&m_mutex, NULL); 253 | } 254 | 255 | multi_threaded_local(const multi_threaded_local&) 256 | { 257 | pthread_mutex_init(&m_mutex, NULL); 258 | } 259 | 260 | virtual ~multi_threaded_local() 261 | { 262 | pthread_mutex_destroy(&m_mutex); 263 | } 264 | 265 | virtual void lock() 266 | { 267 | pthread_mutex_lock(&m_mutex); 268 | } 269 | 270 | virtual void unlock() 271 | { 272 | pthread_mutex_unlock(&m_mutex); 273 | } 274 | 275 | private: 276 | pthread_mutex_t m_mutex; 277 | }; 278 | #endif // _SIGSLOT_HAS_POSIX_THREADS 279 | 280 | template 281 | class lock_block 282 | { 283 | public: 284 | mt_policy *m_mutex; 285 | 286 | lock_block(mt_policy *mtx) 287 | : m_mutex(mtx) 288 | { 289 | m_mutex->lock(); 290 | } 291 | 292 | ~lock_block() 293 | { 294 | m_mutex->unlock(); 295 | } 296 | }; 297 | 298 | template 299 | class has_slots; 300 | 301 | template 302 | class _connection_base0 303 | { 304 | public: 305 | virtual has_slots* getdest() const = 0; 306 | virtual void emit() = 0; 307 | virtual _connection_base0* clone() = 0; 308 | virtual _connection_base0* duplicate(has_slots* pnewdest) = 0; 309 | }; 310 | 311 | template 312 | class _connection_base1 313 | { 314 | public: 315 | virtual has_slots* getdest() const = 0; 316 | virtual void emit(arg1_type) = 0; 317 | virtual _connection_base1* clone() = 0; 318 | virtual _connection_base1* duplicate(has_slots* pnewdest) = 0; 319 | }; 320 | 321 | template 322 | class _connection_base2 323 | { 324 | public: 325 | virtual has_slots* getdest() const = 0; 326 | virtual void emit(arg1_type, arg2_type) = 0; 327 | virtual _connection_base2* clone() = 0; 328 | virtual _connection_base2* duplicate(has_slots* pnewdest) = 0; 329 | }; 330 | 331 | template 332 | class _connection_base3 333 | { 334 | public: 335 | virtual has_slots* getdest() const = 0; 336 | virtual void emit(arg1_type, arg2_type, arg3_type) = 0; 337 | virtual _connection_base3* clone() = 0; 338 | virtual _connection_base3* duplicate(has_slots* pnewdest) = 0; 339 | }; 340 | 341 | template 342 | class _connection_base4 343 | { 344 | public: 345 | virtual has_slots* getdest() const = 0; 346 | virtual void emit(arg1_type, arg2_type, arg3_type, arg4_type) = 0; 347 | virtual _connection_base4* clone() = 0; 348 | virtual _connection_base4* duplicate(has_slots* pnewdest) = 0; 349 | }; 350 | 351 | template 353 | class _connection_base5 354 | { 355 | public: 356 | virtual has_slots* getdest() const = 0; 357 | virtual void emit(arg1_type, arg2_type, arg3_type, arg4_type, 358 | arg5_type) = 0; 359 | virtual _connection_base5* clone() = 0; 361 | virtual _connection_base5* duplicate(has_slots* pnewdest) = 0; 363 | }; 364 | 365 | template 367 | class _connection_base6 368 | { 369 | public: 370 | virtual has_slots* getdest() const = 0; 371 | virtual void emit(arg1_type, arg2_type, arg3_type, arg4_type, arg5_type, 372 | arg6_type) = 0; 373 | virtual _connection_base6* clone() = 0; 375 | virtual _connection_base6* duplicate(has_slots* pnewdest) = 0; 377 | }; 378 | 379 | template 381 | class _connection_base7 382 | { 383 | public: 384 | virtual has_slots* getdest() const = 0; 385 | virtual void emit(arg1_type, arg2_type, arg3_type, arg4_type, arg5_type, 386 | arg6_type, arg7_type) = 0; 387 | virtual _connection_base7* clone() = 0; 389 | virtual _connection_base7* duplicate(has_slots* pnewdest) = 0; 391 | }; 392 | 393 | template 395 | class _connection_base8 396 | { 397 | public: 398 | virtual has_slots* getdest() const = 0; 399 | virtual void emit(arg1_type, arg2_type, arg3_type, arg4_type, arg5_type, 400 | arg6_type, arg7_type, arg8_type) = 0; 401 | virtual _connection_base8* clone() = 0; 403 | virtual _connection_base8* duplicate(has_slots* pnewdest) = 0; 405 | }; 406 | 407 | template 408 | class _signal_base : public mt_policy 409 | { 410 | public: 411 | virtual void slot_disconnect(has_slots* pslot) = 0; 412 | virtual void slot_duplicate(const has_slots* poldslot, has_slots* pnewslot) = 0; 413 | }; 414 | 415 | template 416 | class has_slots : public mt_policy 417 | { 418 | private: 419 | typedef std::set<_signal_base * > sender_set; 420 | typedef typename sender_set::const_iterator const_iterator; 421 | 422 | public: 423 | has_slots() 424 | { 425 | ; 426 | } 427 | 428 | has_slots(const has_slots& hs) 429 | : mt_policy(hs) 430 | { 431 | lock_block lock(this); 432 | const_iterator it = hs.m_senders.begin(); 433 | const_iterator itEnd = hs.m_senders.end(); 434 | 435 | while(it != itEnd) 436 | { 437 | (*it)->slot_duplicate(&hs, this); 438 | m_senders.insert(*it); 439 | ++it; 440 | } 441 | } 442 | 443 | void signal_connect(_signal_base* sender) 444 | { 445 | lock_block lock(this); 446 | m_senders.insert(sender); 447 | } 448 | 449 | void signal_disconnect(_signal_base* sender) 450 | { 451 | lock_block lock(this); 452 | m_senders.erase(sender); 453 | } 454 | 455 | virtual ~has_slots() 456 | { 457 | disconnect_all(); 458 | } 459 | 460 | void disconnect_all() 461 | { 462 | lock_block lock(this); 463 | const_iterator it = m_senders.begin(); 464 | const_iterator itEnd = m_senders.end(); 465 | 466 | while(it != itEnd) 467 | { 468 | (*it)->slot_disconnect(this); 469 | ++it; 470 | } 471 | 472 | m_senders.erase(m_senders.begin(), m_senders.end()); 473 | } 474 | 475 | private: 476 | sender_set m_senders; 477 | }; 478 | 479 | template 480 | class _signal_base0 : public _signal_base 481 | { 482 | public: 483 | typedef std::list<_connection_base0 *> connections_list; 484 | 485 | _signal_base0() 486 | { 487 | ; 488 | } 489 | 490 | _signal_base0(const _signal_base0& s) 491 | : _signal_base(s) 492 | { 493 | lock_block lock(this); 494 | connections_list::const_iterator it = s.m_connected_slots.begin(); 495 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 496 | 497 | while(it != itEnd) 498 | { 499 | (*it)->getdest()->signal_connect(this); 500 | m_connected_slots.push_back((*it)->clone()); 501 | 502 | ++it; 503 | } 504 | } 505 | 506 | ~_signal_base0() 507 | { 508 | disconnect_all(); 509 | } 510 | 511 | void disconnect_all() 512 | { 513 | lock_block lock(this); 514 | connections_list::const_iterator it = m_connected_slots.begin(); 515 | connections_list::const_iterator itEnd = m_connected_slots.end(); 516 | 517 | while(it != itEnd) 518 | { 519 | (*it)->getdest()->signal_disconnect(this); 520 | delete *it; 521 | 522 | ++it; 523 | } 524 | 525 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 526 | } 527 | 528 | void disconnect(has_slots* pclass) 529 | { 530 | lock_block lock(this); 531 | connections_list::iterator it = m_connected_slots.begin(); 532 | connections_list::iterator itEnd = m_connected_slots.end(); 533 | 534 | while(it != itEnd) 535 | { 536 | if((*it)->getdest() == pclass) 537 | { 538 | delete *it; 539 | m_connected_slots.erase(it); 540 | pclass->signal_disconnect(this); 541 | return; 542 | } 543 | 544 | ++it; 545 | } 546 | } 547 | 548 | void slot_disconnect(has_slots* pslot) 549 | { 550 | lock_block lock(this); 551 | connections_list::iterator it = m_connected_slots.begin(); 552 | connections_list::iterator itEnd = m_connected_slots.end(); 553 | 554 | while(it != itEnd) 555 | { 556 | connections_list::iterator itNext = it; 557 | ++itNext; 558 | 559 | if((*it)->getdest() == pslot) 560 | { 561 | m_connected_slots.erase(it); 562 | // delete *it; 563 | } 564 | 565 | it = itNext; 566 | } 567 | } 568 | 569 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 570 | { 571 | lock_block lock(this); 572 | connections_list::iterator it = m_connected_slots.begin(); 573 | connections_list::iterator itEnd = m_connected_slots.end(); 574 | 575 | while(it != itEnd) 576 | { 577 | if((*it)->getdest() == oldtarget) 578 | { 579 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 580 | } 581 | 582 | ++it; 583 | } 584 | } 585 | 586 | protected: 587 | connections_list m_connected_slots; 588 | }; 589 | 590 | template 591 | class _signal_base1 : public _signal_base 592 | { 593 | public: 594 | typedef std::list<_connection_base1 *> connections_list; 595 | 596 | _signal_base1() 597 | { 598 | ; 599 | } 600 | 601 | _signal_base1(const _signal_base1& s) 602 | : _signal_base(s) 603 | { 604 | lock_block lock(this); 605 | connections_list::const_iterator it = s.m_connected_slots.begin(); 606 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 607 | 608 | while(it != itEnd) 609 | { 610 | (*it)->getdest()->signal_connect(this); 611 | m_connected_slots.push_back((*it)->clone()); 612 | 613 | ++it; 614 | } 615 | } 616 | 617 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 618 | { 619 | lock_block lock(this); 620 | connections_list::iterator it = m_connected_slots.begin(); 621 | connections_list::iterator itEnd = m_connected_slots.end(); 622 | 623 | while(it != itEnd) 624 | { 625 | if((*it)->getdest() == oldtarget) 626 | { 627 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 628 | } 629 | 630 | ++it; 631 | } 632 | } 633 | 634 | ~_signal_base1() 635 | { 636 | disconnect_all(); 637 | } 638 | 639 | void disconnect_all() 640 | { 641 | lock_block lock(this); 642 | connections_list::const_iterator it = m_connected_slots.begin(); 643 | connections_list::const_iterator itEnd = m_connected_slots.end(); 644 | 645 | while(it != itEnd) 646 | { 647 | (*it)->getdest()->signal_disconnect(this); 648 | delete *it; 649 | 650 | ++it; 651 | } 652 | 653 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 654 | } 655 | 656 | void disconnect(has_slots* pclass) 657 | { 658 | lock_block lock(this); 659 | connections_list::iterator it = m_connected_slots.begin(); 660 | connections_list::iterator itEnd = m_connected_slots.end(); 661 | 662 | while(it != itEnd) 663 | { 664 | if((*it)->getdest() == pclass) 665 | { 666 | delete *it; 667 | m_connected_slots.erase(it); 668 | pclass->signal_disconnect(this); 669 | return; 670 | } 671 | 672 | ++it; 673 | } 674 | } 675 | 676 | void slot_disconnect(has_slots* pslot) 677 | { 678 | lock_block lock(this); 679 | connections_list::iterator it = m_connected_slots.begin(); 680 | connections_list::iterator itEnd = m_connected_slots.end(); 681 | 682 | while(it != itEnd) 683 | { 684 | connections_list::iterator itNext = it; 685 | ++itNext; 686 | 687 | if((*it)->getdest() == pslot) 688 | { 689 | m_connected_slots.erase(it); 690 | // delete *it; 691 | } 692 | 693 | it = itNext; 694 | } 695 | } 696 | 697 | 698 | protected: 699 | connections_list m_connected_slots; 700 | }; 701 | 702 | template 703 | class _signal_base2 : public _signal_base 704 | { 705 | public: 706 | typedef std::list<_connection_base2 *> 707 | connections_list; 708 | 709 | _signal_base2() 710 | { 711 | ; 712 | } 713 | 714 | _signal_base2(const _signal_base2& s) 715 | : _signal_base(s) 716 | { 717 | lock_block lock(this); 718 | connections_list::const_iterator it = s.m_connected_slots.begin(); 719 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 720 | 721 | while(it != itEnd) 722 | { 723 | (*it)->getdest()->signal_connect(this); 724 | m_connected_slots.push_back((*it)->clone()); 725 | 726 | ++it; 727 | } 728 | } 729 | 730 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 731 | { 732 | lock_block lock(this); 733 | connections_list::iterator it = m_connected_slots.begin(); 734 | connections_list::iterator itEnd = m_connected_slots.end(); 735 | 736 | while(it != itEnd) 737 | { 738 | if((*it)->getdest() == oldtarget) 739 | { 740 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 741 | } 742 | 743 | ++it; 744 | } 745 | } 746 | 747 | ~_signal_base2() 748 | { 749 | disconnect_all(); 750 | } 751 | 752 | void disconnect_all() 753 | { 754 | lock_block lock(this); 755 | connections_list::const_iterator it = m_connected_slots.begin(); 756 | connections_list::const_iterator itEnd = m_connected_slots.end(); 757 | 758 | while(it != itEnd) 759 | { 760 | (*it)->getdest()->signal_disconnect(this); 761 | delete *it; 762 | 763 | ++it; 764 | } 765 | 766 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 767 | } 768 | 769 | void disconnect(has_slots* pclass) 770 | { 771 | lock_block lock(this); 772 | connections_list::iterator it = m_connected_slots.begin(); 773 | connections_list::iterator itEnd = m_connected_slots.end(); 774 | 775 | while(it != itEnd) 776 | { 777 | if((*it)->getdest() == pclass) 778 | { 779 | delete *it; 780 | m_connected_slots.erase(it); 781 | pclass->signal_disconnect(this); 782 | return; 783 | } 784 | 785 | ++it; 786 | } 787 | } 788 | 789 | void slot_disconnect(has_slots* pslot) 790 | { 791 | lock_block lock(this); 792 | connections_list::iterator it = m_connected_slots.begin(); 793 | connections_list::iterator itEnd = m_connected_slots.end(); 794 | 795 | while(it != itEnd) 796 | { 797 | connections_list::iterator itNext = it; 798 | ++itNext; 799 | 800 | if((*it)->getdest() == pslot) 801 | { 802 | m_connected_slots.erase(it); 803 | // delete *it; 804 | } 805 | 806 | it = itNext; 807 | } 808 | } 809 | 810 | protected: 811 | connections_list m_connected_slots; 812 | }; 813 | 814 | template 815 | class _signal_base3 : public _signal_base 816 | { 817 | public: 818 | typedef std::list<_connection_base3 *> 819 | connections_list; 820 | 821 | _signal_base3() 822 | { 823 | ; 824 | } 825 | 826 | _signal_base3(const _signal_base3& s) 827 | : _signal_base(s) 828 | { 829 | lock_block lock(this); 830 | connections_list::const_iterator it = s.m_connected_slots.begin(); 831 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 832 | 833 | while(it != itEnd) 834 | { 835 | (*it)->getdest()->signal_connect(this); 836 | m_connected_slots.push_back((*it)->clone()); 837 | 838 | ++it; 839 | } 840 | } 841 | 842 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 843 | { 844 | lock_block lock(this); 845 | connections_list::iterator it = m_connected_slots.begin(); 846 | connections_list::iterator itEnd = m_connected_slots.end(); 847 | 848 | while(it != itEnd) 849 | { 850 | if((*it)->getdest() == oldtarget) 851 | { 852 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 853 | } 854 | 855 | ++it; 856 | } 857 | } 858 | 859 | ~_signal_base3() 860 | { 861 | disconnect_all(); 862 | } 863 | 864 | void disconnect_all() 865 | { 866 | lock_block lock(this); 867 | connections_list::const_iterator it = m_connected_slots.begin(); 868 | connections_list::const_iterator itEnd = m_connected_slots.end(); 869 | 870 | while(it != itEnd) 871 | { 872 | (*it)->getdest()->signal_disconnect(this); 873 | delete *it; 874 | 875 | ++it; 876 | } 877 | 878 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 879 | } 880 | 881 | void disconnect(has_slots* pclass) 882 | { 883 | lock_block lock(this); 884 | connections_list::iterator it = m_connected_slots.begin(); 885 | connections_list::iterator itEnd = m_connected_slots.end(); 886 | 887 | while(it != itEnd) 888 | { 889 | if((*it)->getdest() == pclass) 890 | { 891 | delete *it; 892 | m_connected_slots.erase(it); 893 | pclass->signal_disconnect(this); 894 | return; 895 | } 896 | 897 | ++it; 898 | } 899 | } 900 | 901 | void slot_disconnect(has_slots* pslot) 902 | { 903 | lock_block lock(this); 904 | connections_list::iterator it = m_connected_slots.begin(); 905 | connections_list::iterator itEnd = m_connected_slots.end(); 906 | 907 | while(it != itEnd) 908 | { 909 | connections_list::iterator itNext = it; 910 | ++itNext; 911 | 912 | if((*it)->getdest() == pslot) 913 | { 914 | m_connected_slots.erase(it); 915 | // delete *it; 916 | } 917 | 918 | it = itNext; 919 | } 920 | } 921 | 922 | protected: 923 | connections_list m_connected_slots; 924 | }; 925 | 926 | template 927 | class _signal_base4 : public _signal_base 928 | { 929 | public: 930 | typedef std::list<_connection_base4 *> connections_list; 932 | 933 | _signal_base4() 934 | { 935 | ; 936 | } 937 | 938 | _signal_base4(const _signal_base4& s) 939 | : _signal_base(s) 940 | { 941 | lock_block lock(this); 942 | connections_list::const_iterator it = s.m_connected_slots.begin(); 943 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 944 | 945 | while(it != itEnd) 946 | { 947 | (*it)->getdest()->signal_connect(this); 948 | m_connected_slots.push_back((*it)->clone()); 949 | 950 | ++it; 951 | } 952 | } 953 | 954 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 955 | { 956 | lock_block lock(this); 957 | connections_list::iterator it = m_connected_slots.begin(); 958 | connections_list::iterator itEnd = m_connected_slots.end(); 959 | 960 | while(it != itEnd) 961 | { 962 | if((*it)->getdest() == oldtarget) 963 | { 964 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 965 | } 966 | 967 | ++it; 968 | } 969 | } 970 | 971 | ~_signal_base4() 972 | { 973 | disconnect_all(); 974 | } 975 | 976 | void disconnect_all() 977 | { 978 | lock_block lock(this); 979 | connections_list::const_iterator it = m_connected_slots.begin(); 980 | connections_list::const_iterator itEnd = m_connected_slots.end(); 981 | 982 | while(it != itEnd) 983 | { 984 | (*it)->getdest()->signal_disconnect(this); 985 | delete *it; 986 | 987 | ++it; 988 | } 989 | 990 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 991 | } 992 | 993 | void disconnect(has_slots* pclass) 994 | { 995 | lock_block lock(this); 996 | connections_list::iterator it = m_connected_slots.begin(); 997 | connections_list::iterator itEnd = m_connected_slots.end(); 998 | 999 | while(it != itEnd) 1000 | { 1001 | if((*it)->getdest() == pclass) 1002 | { 1003 | delete *it; 1004 | m_connected_slots.erase(it); 1005 | pclass->signal_disconnect(this); 1006 | return; 1007 | } 1008 | 1009 | ++it; 1010 | } 1011 | } 1012 | 1013 | void slot_disconnect(has_slots* pslot) 1014 | { 1015 | lock_block lock(this); 1016 | connections_list::iterator it = m_connected_slots.begin(); 1017 | connections_list::iterator itEnd = m_connected_slots.end(); 1018 | 1019 | while(it != itEnd) 1020 | { 1021 | connections_list::iterator itNext = it; 1022 | ++itNext; 1023 | 1024 | if((*it)->getdest() == pslot) 1025 | { 1026 | m_connected_slots.erase(it); 1027 | // delete *it; 1028 | } 1029 | 1030 | it = itNext; 1031 | } 1032 | } 1033 | 1034 | protected: 1035 | connections_list m_connected_slots; 1036 | }; 1037 | 1038 | template 1040 | class _signal_base5 : public _signal_base 1041 | { 1042 | public: 1043 | typedef std::list<_connection_base5 *> connections_list; 1045 | 1046 | _signal_base5() 1047 | { 1048 | ; 1049 | } 1050 | 1051 | _signal_base5(const _signal_base5& s) 1053 | : _signal_base(s) 1054 | { 1055 | lock_block lock(this); 1056 | connections_list::const_iterator it = s.m_connected_slots.begin(); 1057 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 1058 | 1059 | while(it != itEnd) 1060 | { 1061 | (*it)->getdest()->signal_connect(this); 1062 | m_connected_slots.push_back((*it)->clone()); 1063 | 1064 | ++it; 1065 | } 1066 | } 1067 | 1068 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 1069 | { 1070 | lock_block lock(this); 1071 | connections_list::iterator it = m_connected_slots.begin(); 1072 | connections_list::iterator itEnd = m_connected_slots.end(); 1073 | 1074 | while(it != itEnd) 1075 | { 1076 | if((*it)->getdest() == oldtarget) 1077 | { 1078 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 1079 | } 1080 | 1081 | ++it; 1082 | } 1083 | } 1084 | 1085 | ~_signal_base5() 1086 | { 1087 | disconnect_all(); 1088 | } 1089 | 1090 | void disconnect_all() 1091 | { 1092 | lock_block lock(this); 1093 | connections_list::const_iterator it = m_connected_slots.begin(); 1094 | connections_list::const_iterator itEnd = m_connected_slots.end(); 1095 | 1096 | while(it != itEnd) 1097 | { 1098 | (*it)->getdest()->signal_disconnect(this); 1099 | delete *it; 1100 | 1101 | ++it; 1102 | } 1103 | 1104 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 1105 | } 1106 | 1107 | void disconnect(has_slots* pclass) 1108 | { 1109 | lock_block lock(this); 1110 | connections_list::iterator it = m_connected_slots.begin(); 1111 | connections_list::iterator itEnd = m_connected_slots.end(); 1112 | 1113 | while(it != itEnd) 1114 | { 1115 | if((*it)->getdest() == pclass) 1116 | { 1117 | delete *it; 1118 | m_connected_slots.erase(it); 1119 | pclass->signal_disconnect(this); 1120 | return; 1121 | } 1122 | 1123 | ++it; 1124 | } 1125 | } 1126 | 1127 | void slot_disconnect(has_slots* pslot) 1128 | { 1129 | lock_block lock(this); 1130 | connections_list::iterator it = m_connected_slots.begin(); 1131 | connections_list::iterator itEnd = m_connected_slots.end(); 1132 | 1133 | while(it != itEnd) 1134 | { 1135 | connections_list::iterator itNext = it; 1136 | ++itNext; 1137 | 1138 | if((*it)->getdest() == pslot) 1139 | { 1140 | m_connected_slots.erase(it); 1141 | // delete *it; 1142 | } 1143 | 1144 | it = itNext; 1145 | } 1146 | } 1147 | 1148 | protected: 1149 | connections_list m_connected_slots; 1150 | }; 1151 | 1152 | template 1154 | class _signal_base6 : public _signal_base 1155 | { 1156 | public: 1157 | typedef std::list<_connection_base6 *> connections_list; 1159 | 1160 | _signal_base6() 1161 | { 1162 | ; 1163 | } 1164 | 1165 | _signal_base6(const _signal_base6& s) 1167 | : _signal_base(s) 1168 | { 1169 | lock_block lock(this); 1170 | connections_list::const_iterator it = s.m_connected_slots.begin(); 1171 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 1172 | 1173 | while(it != itEnd) 1174 | { 1175 | (*it)->getdest()->signal_connect(this); 1176 | m_connected_slots.push_back((*it)->clone()); 1177 | 1178 | ++it; 1179 | } 1180 | } 1181 | 1182 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 1183 | { 1184 | lock_block lock(this); 1185 | connections_list::iterator it = m_connected_slots.begin(); 1186 | connections_list::iterator itEnd = m_connected_slots.end(); 1187 | 1188 | while(it != itEnd) 1189 | { 1190 | if((*it)->getdest() == oldtarget) 1191 | { 1192 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 1193 | } 1194 | 1195 | ++it; 1196 | } 1197 | } 1198 | 1199 | ~_signal_base6() 1200 | { 1201 | disconnect_all(); 1202 | } 1203 | 1204 | void disconnect_all() 1205 | { 1206 | lock_block lock(this); 1207 | connections_list::const_iterator it = m_connected_slots.begin(); 1208 | connections_list::const_iterator itEnd = m_connected_slots.end(); 1209 | 1210 | while(it != itEnd) 1211 | { 1212 | (*it)->getdest()->signal_disconnect(this); 1213 | delete *it; 1214 | 1215 | ++it; 1216 | } 1217 | 1218 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 1219 | } 1220 | 1221 | void disconnect(has_slots* pclass) 1222 | { 1223 | lock_block lock(this); 1224 | connections_list::iterator it = m_connected_slots.begin(); 1225 | connections_list::iterator itEnd = m_connected_slots.end(); 1226 | 1227 | while(it != itEnd) 1228 | { 1229 | if((*it)->getdest() == pclass) 1230 | { 1231 | delete *it; 1232 | m_connected_slots.erase(it); 1233 | pclass->signal_disconnect(this); 1234 | return; 1235 | } 1236 | 1237 | ++it; 1238 | } 1239 | } 1240 | 1241 | void slot_disconnect(has_slots* pslot) 1242 | { 1243 | lock_block lock(this); 1244 | connections_list::iterator it = m_connected_slots.begin(); 1245 | connections_list::iterator itEnd = m_connected_slots.end(); 1246 | 1247 | while(it != itEnd) 1248 | { 1249 | connections_list::iterator itNext = it; 1250 | ++itNext; 1251 | 1252 | if((*it)->getdest() == pslot) 1253 | { 1254 | m_connected_slots.erase(it); 1255 | // delete *it; 1256 | } 1257 | 1258 | it = itNext; 1259 | } 1260 | } 1261 | 1262 | protected: 1263 | connections_list m_connected_slots; 1264 | }; 1265 | 1266 | template 1268 | class _signal_base7 : public _signal_base 1269 | { 1270 | public: 1271 | typedef std::list<_connection_base7 *> connections_list; 1273 | 1274 | _signal_base7() 1275 | { 1276 | ; 1277 | } 1278 | 1279 | _signal_base7(const _signal_base7& s) 1281 | : _signal_base(s) 1282 | { 1283 | lock_block lock(this); 1284 | connections_list::const_iterator it = s.m_connected_slots.begin(); 1285 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 1286 | 1287 | while(it != itEnd) 1288 | { 1289 | (*it)->getdest()->signal_connect(this); 1290 | m_connected_slots.push_back((*it)->clone()); 1291 | 1292 | ++it; 1293 | } 1294 | } 1295 | 1296 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 1297 | { 1298 | lock_block lock(this); 1299 | connections_list::iterator it = m_connected_slots.begin(); 1300 | connections_list::iterator itEnd = m_connected_slots.end(); 1301 | 1302 | while(it != itEnd) 1303 | { 1304 | if((*it)->getdest() == oldtarget) 1305 | { 1306 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 1307 | } 1308 | 1309 | ++it; 1310 | } 1311 | } 1312 | 1313 | ~_signal_base7() 1314 | { 1315 | disconnect_all(); 1316 | } 1317 | 1318 | void disconnect_all() 1319 | { 1320 | lock_block lock(this); 1321 | connections_list::const_iterator it = m_connected_slots.begin(); 1322 | connections_list::const_iterator itEnd = m_connected_slots.end(); 1323 | 1324 | while(it != itEnd) 1325 | { 1326 | (*it)->getdest()->signal_disconnect(this); 1327 | delete *it; 1328 | 1329 | ++it; 1330 | } 1331 | 1332 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 1333 | } 1334 | 1335 | void disconnect(has_slots* pclass) 1336 | { 1337 | lock_block lock(this); 1338 | connections_list::iterator it = m_connected_slots.begin(); 1339 | connections_list::iterator itEnd = m_connected_slots.end(); 1340 | 1341 | while(it != itEnd) 1342 | { 1343 | if((*it)->getdest() == pclass) 1344 | { 1345 | delete *it; 1346 | m_connected_slots.erase(it); 1347 | pclass->signal_disconnect(this); 1348 | return; 1349 | } 1350 | 1351 | ++it; 1352 | } 1353 | } 1354 | 1355 | void slot_disconnect(has_slots* pslot) 1356 | { 1357 | lock_block lock(this); 1358 | connections_list::iterator it = m_connected_slots.begin(); 1359 | connections_list::iterator itEnd = m_connected_slots.end(); 1360 | 1361 | while(it != itEnd) 1362 | { 1363 | connections_list::iterator itNext = it; 1364 | ++itNext; 1365 | 1366 | if((*it)->getdest() == pslot) 1367 | { 1368 | m_connected_slots.erase(it); 1369 | // delete *it; 1370 | } 1371 | 1372 | it = itNext; 1373 | } 1374 | } 1375 | 1376 | protected: 1377 | connections_list m_connected_slots; 1378 | }; 1379 | 1380 | template 1382 | class _signal_base8 : public _signal_base 1383 | { 1384 | public: 1385 | typedef std::list<_connection_base8 *> 1387 | connections_list; 1388 | 1389 | _signal_base8() 1390 | { 1391 | ; 1392 | } 1393 | 1394 | _signal_base8(const _signal_base8& s) 1396 | : _signal_base(s) 1397 | { 1398 | lock_block lock(this); 1399 | connections_list::const_iterator it = s.m_connected_slots.begin(); 1400 | connections_list::const_iterator itEnd = s.m_connected_slots.end(); 1401 | 1402 | while(it != itEnd) 1403 | { 1404 | (*it)->getdest()->signal_connect(this); 1405 | m_connected_slots.push_back((*it)->clone()); 1406 | 1407 | ++it; 1408 | } 1409 | } 1410 | 1411 | void slot_duplicate(const has_slots* oldtarget, has_slots* newtarget) 1412 | { 1413 | lock_block lock(this); 1414 | connections_list::iterator it = m_connected_slots.begin(); 1415 | connections_list::iterator itEnd = m_connected_slots.end(); 1416 | 1417 | while(it != itEnd) 1418 | { 1419 | if((*it)->getdest() == oldtarget) 1420 | { 1421 | m_connected_slots.push_back((*it)->duplicate(newtarget)); 1422 | } 1423 | 1424 | ++it; 1425 | } 1426 | } 1427 | 1428 | ~_signal_base8() 1429 | { 1430 | disconnect_all(); 1431 | } 1432 | 1433 | void disconnect_all() 1434 | { 1435 | lock_block lock(this); 1436 | connections_list::const_iterator it = m_connected_slots.begin(); 1437 | connections_list::const_iterator itEnd = m_connected_slots.end(); 1438 | 1439 | while(it != itEnd) 1440 | { 1441 | (*it)->getdest()->signal_disconnect(this); 1442 | delete *it; 1443 | 1444 | ++it; 1445 | } 1446 | 1447 | m_connected_slots.erase(m_connected_slots.begin(), m_connected_slots.end()); 1448 | } 1449 | 1450 | void disconnect(has_slots* pclass) 1451 | { 1452 | lock_block lock(this); 1453 | connections_list::iterator it = m_connected_slots.begin(); 1454 | connections_list::iterator itEnd = m_connected_slots.end(); 1455 | 1456 | while(it != itEnd) 1457 | { 1458 | if((*it)->getdest() == pclass) 1459 | { 1460 | delete *it; 1461 | m_connected_slots.erase(it); 1462 | pclass->signal_disconnect(this); 1463 | return; 1464 | } 1465 | 1466 | ++it; 1467 | } 1468 | } 1469 | 1470 | void slot_disconnect(has_slots* pslot) 1471 | { 1472 | lock_block lock(this); 1473 | connections_list::iterator it = m_connected_slots.begin(); 1474 | connections_list::iterator itEnd = m_connected_slots.end(); 1475 | 1476 | while(it != itEnd) 1477 | { 1478 | connections_list::iterator itNext = it; 1479 | ++itNext; 1480 | 1481 | if((*it)->getdest() == pslot) 1482 | { 1483 | m_connected_slots.erase(it); 1484 | // delete *it; 1485 | } 1486 | 1487 | it = itNext; 1488 | } 1489 | } 1490 | 1491 | protected: 1492 | connections_list m_connected_slots; 1493 | }; 1494 | 1495 | 1496 | template 1497 | class _connection0 : public _connection_base0 1498 | { 1499 | public: 1500 | _connection0() 1501 | { 1502 | pobject = NULL; 1503 | pmemfun = NULL; 1504 | } 1505 | 1506 | _connection0(dest_type* pobject, void (dest_type::*pmemfun)()) 1507 | { 1508 | m_pobject = pobject; 1509 | m_pmemfun = pmemfun; 1510 | } 1511 | 1512 | virtual _connection_base0* clone() 1513 | { 1514 | return new _connection0(*this); 1515 | } 1516 | 1517 | virtual _connection_base0* duplicate(has_slots* pnewdest) 1518 | { 1519 | return new _connection0((dest_type *)pnewdest, m_pmemfun); 1520 | } 1521 | 1522 | virtual void emit() 1523 | { 1524 | (m_pobject->*m_pmemfun)(); 1525 | } 1526 | 1527 | virtual has_slots* getdest() const 1528 | { 1529 | return m_pobject; 1530 | } 1531 | 1532 | private: 1533 | dest_type* m_pobject; 1534 | void (dest_type::* m_pmemfun)(); 1535 | }; 1536 | 1537 | template 1538 | class _connection1 : public _connection_base1 1539 | { 1540 | public: 1541 | _connection1() 1542 | { 1543 | pobject = NULL; 1544 | pmemfun = NULL; 1545 | } 1546 | 1547 | _connection1(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type)) 1548 | { 1549 | m_pobject = pobject; 1550 | m_pmemfun = pmemfun; 1551 | } 1552 | 1553 | virtual _connection_base1* clone() 1554 | { 1555 | return new _connection1(*this); 1556 | } 1557 | 1558 | virtual _connection_base1* duplicate(has_slots* pnewdest) 1559 | { 1560 | return new _connection1((dest_type *)pnewdest, m_pmemfun); 1561 | } 1562 | 1563 | virtual void emit(arg1_type a1) 1564 | { 1565 | (m_pobject->*m_pmemfun)(a1); 1566 | } 1567 | 1568 | virtual has_slots* getdest() const 1569 | { 1570 | return m_pobject; 1571 | } 1572 | 1573 | private: 1574 | dest_type* m_pobject; 1575 | void (dest_type::* m_pmemfun)(arg1_type); 1576 | }; 1577 | 1578 | template 1579 | class _connection2 : public _connection_base2 1580 | { 1581 | public: 1582 | _connection2() 1583 | { 1584 | pobject = NULL; 1585 | pmemfun = NULL; 1586 | } 1587 | 1588 | _connection2(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1589 | arg2_type)) 1590 | { 1591 | m_pobject = pobject; 1592 | m_pmemfun = pmemfun; 1593 | } 1594 | 1595 | virtual _connection_base2* clone() 1596 | { 1597 | return new _connection2(*this); 1598 | } 1599 | 1600 | virtual _connection_base2* duplicate(has_slots* pnewdest) 1601 | { 1602 | return new _connection2((dest_type *)pnewdest, m_pmemfun); 1603 | } 1604 | 1605 | virtual void emit(arg1_type a1, arg2_type a2) 1606 | { 1607 | (m_pobject->*m_pmemfun)(a1, a2); 1608 | } 1609 | 1610 | virtual has_slots* getdest() const 1611 | { 1612 | return m_pobject; 1613 | } 1614 | 1615 | private: 1616 | dest_type* m_pobject; 1617 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type); 1618 | }; 1619 | 1620 | template 1621 | class _connection3 : public _connection_base3 1622 | { 1623 | public: 1624 | _connection3() 1625 | { 1626 | pobject = NULL; 1627 | pmemfun = NULL; 1628 | } 1629 | 1630 | _connection3(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1631 | arg2_type, arg3_type)) 1632 | { 1633 | m_pobject = pobject; 1634 | m_pmemfun = pmemfun; 1635 | } 1636 | 1637 | virtual _connection_base3* clone() 1638 | { 1639 | return new _connection3(*this); 1640 | } 1641 | 1642 | virtual _connection_base3* duplicate(has_slots* pnewdest) 1643 | { 1644 | return new _connection3((dest_type *)pnewdest, m_pmemfun); 1645 | } 1646 | 1647 | virtual void emit(arg1_type a1, arg2_type a2, arg3_type a3) 1648 | { 1649 | (m_pobject->*m_pmemfun)(a1, a2, a3); 1650 | } 1651 | 1652 | virtual has_slots* getdest() const 1653 | { 1654 | return m_pobject; 1655 | } 1656 | 1657 | private: 1658 | dest_type* m_pobject; 1659 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type, arg3_type); 1660 | }; 1661 | 1662 | template 1664 | class _connection4 : public _connection_base4 1666 | { 1667 | public: 1668 | _connection4() 1669 | { 1670 | pobject = NULL; 1671 | pmemfun = NULL; 1672 | } 1673 | 1674 | _connection4(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1675 | arg2_type, arg3_type, arg4_type)) 1676 | { 1677 | m_pobject = pobject; 1678 | m_pmemfun = pmemfun; 1679 | } 1680 | 1681 | virtual _connection_base4* clone() 1682 | { 1683 | return new _connection4(*this); 1684 | } 1685 | 1686 | virtual _connection_base4* duplicate(has_slots* pnewdest) 1687 | { 1688 | return new _connection4((dest_type *)pnewdest, m_pmemfun); 1689 | } 1690 | 1691 | virtual void emit(arg1_type a1, arg2_type a2, arg3_type a3, 1692 | arg4_type a4) 1693 | { 1694 | (m_pobject->*m_pmemfun)(a1, a2, a3, a4); 1695 | } 1696 | 1697 | virtual has_slots* getdest() const 1698 | { 1699 | return m_pobject; 1700 | } 1701 | 1702 | private: 1703 | dest_type* m_pobject; 1704 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type, arg3_type, 1705 | arg4_type); 1706 | }; 1707 | 1708 | template 1710 | class _connection5 : public _connection_base5 1712 | { 1713 | public: 1714 | _connection5() 1715 | { 1716 | pobject = NULL; 1717 | pmemfun = NULL; 1718 | } 1719 | 1720 | _connection5(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1721 | arg2_type, arg3_type, arg4_type, arg5_type)) 1722 | { 1723 | m_pobject = pobject; 1724 | m_pmemfun = pmemfun; 1725 | } 1726 | 1727 | virtual _connection_base5* clone() 1729 | { 1730 | return new _connection5(*this); 1732 | } 1733 | 1734 | virtual _connection_base5* duplicate(has_slots* pnewdest) 1736 | { 1737 | return new _connection5((dest_type *)pnewdest, m_pmemfun); 1739 | } 1740 | 1741 | virtual void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 1742 | arg5_type a5) 1743 | { 1744 | (m_pobject->*m_pmemfun)(a1, a2, a3, a4, a5); 1745 | } 1746 | 1747 | virtual has_slots* getdest() const 1748 | { 1749 | return m_pobject; 1750 | } 1751 | 1752 | private: 1753 | dest_type* m_pobject; 1754 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type, arg3_type, arg4_type, 1755 | arg5_type); 1756 | }; 1757 | 1758 | template 1760 | class _connection6 : public _connection_base6 1762 | { 1763 | public: 1764 | _connection6() 1765 | { 1766 | pobject = NULL; 1767 | pmemfun = NULL; 1768 | } 1769 | 1770 | _connection6(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1771 | arg2_type, arg3_type, arg4_type, arg5_type, arg6_type)) 1772 | { 1773 | m_pobject = pobject; 1774 | m_pmemfun = pmemfun; 1775 | } 1776 | 1777 | virtual _connection_base6* clone() 1779 | { 1780 | return new _connection6(*this); 1782 | } 1783 | 1784 | virtual _connection_base6* duplicate(has_slots* pnewdest) 1786 | { 1787 | return new _connection6((dest_type *)pnewdest, m_pmemfun); 1789 | } 1790 | 1791 | virtual void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 1792 | arg5_type a5, arg6_type a6) 1793 | { 1794 | (m_pobject->*m_pmemfun)(a1, a2, a3, a4, a5, a6); 1795 | } 1796 | 1797 | virtual has_slots* getdest() const 1798 | { 1799 | return m_pobject; 1800 | } 1801 | 1802 | private: 1803 | dest_type* m_pobject; 1804 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type, arg3_type, arg4_type, 1805 | arg5_type, arg6_type); 1806 | }; 1807 | 1808 | template 1810 | class _connection7 : public _connection_base7 1812 | { 1813 | public: 1814 | _connection7() 1815 | { 1816 | pobject = NULL; 1817 | pmemfun = NULL; 1818 | } 1819 | 1820 | _connection7(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1821 | arg2_type, arg3_type, arg4_type, arg5_type, arg6_type, arg7_type)) 1822 | { 1823 | m_pobject = pobject; 1824 | m_pmemfun = pmemfun; 1825 | } 1826 | 1827 | virtual _connection_base7* clone() 1829 | { 1830 | return new _connection7(*this); 1832 | } 1833 | 1834 | virtual _connection_base7* duplicate(has_slots* pnewdest) 1836 | { 1837 | return new _connection7((dest_type *)pnewdest, m_pmemfun); 1839 | } 1840 | 1841 | virtual void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 1842 | arg5_type a5, arg6_type a6, arg7_type a7) 1843 | { 1844 | (m_pobject->*m_pmemfun)(a1, a2, a3, a4, a5, a6, a7); 1845 | } 1846 | 1847 | virtual has_slots* getdest() const 1848 | { 1849 | return m_pobject; 1850 | } 1851 | 1852 | private: 1853 | dest_type* m_pobject; 1854 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type, arg3_type, arg4_type, 1855 | arg5_type, arg6_type, arg7_type); 1856 | }; 1857 | 1858 | template 1861 | class _connection8 : public _connection_base8 1863 | { 1864 | public: 1865 | _connection8() 1866 | { 1867 | pobject = NULL; 1868 | pmemfun = NULL; 1869 | } 1870 | 1871 | _connection8(dest_type* pobject, void (dest_type::*pmemfun)(arg1_type, 1872 | arg2_type, arg3_type, arg4_type, arg5_type, arg6_type, 1873 | arg7_type, arg8_type)) 1874 | { 1875 | m_pobject = pobject; 1876 | m_pmemfun = pmemfun; 1877 | } 1878 | 1879 | virtual _connection_base8* clone() 1881 | { 1882 | return new _connection8(*this); 1884 | } 1885 | 1886 | virtual _connection_base8* duplicate(has_slots* pnewdest) 1888 | { 1889 | return new _connection8((dest_type *)pnewdest, m_pmemfun); 1891 | } 1892 | 1893 | virtual void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 1894 | arg5_type a5, arg6_type a6, arg7_type a7, arg8_type a8) 1895 | { 1896 | (m_pobject->*m_pmemfun)(a1, a2, a3, a4, a5, a6, a7, a8); 1897 | } 1898 | 1899 | virtual has_slots* getdest() const 1900 | { 1901 | return m_pobject; 1902 | } 1903 | 1904 | private: 1905 | dest_type* m_pobject; 1906 | void (dest_type::* m_pmemfun)(arg1_type, arg2_type, arg3_type, arg4_type, 1907 | arg5_type, arg6_type, arg7_type, arg8_type); 1908 | }; 1909 | 1910 | template 1911 | class signal0 : public _signal_base0 1912 | { 1913 | public: 1914 | signal0() 1915 | { 1916 | ; 1917 | } 1918 | 1919 | signal0(const signal0& s) 1920 | : _signal_base0(s) 1921 | { 1922 | ; 1923 | } 1924 | 1925 | template 1926 | void connect(desttype* pclass, void (desttype::*pmemfun)()) 1927 | { 1928 | lock_block lock(this); 1929 | _connection0* conn = 1930 | new _connection0(pclass, pmemfun); 1931 | m_connected_slots.push_back(conn); 1932 | pclass->signal_connect(this); 1933 | } 1934 | 1935 | void emit() 1936 | { 1937 | lock_block lock(this); 1938 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 1939 | connections_list::const_iterator itEnd = m_connected_slots.end(); 1940 | 1941 | while(it != itEnd) 1942 | { 1943 | itNext = it; 1944 | ++itNext; 1945 | 1946 | (*it)->emit(); 1947 | 1948 | it = itNext; 1949 | } 1950 | } 1951 | 1952 | void operator()() 1953 | { 1954 | lock_block lock(this); 1955 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 1956 | connections_list::const_iterator itEnd = m_connected_slots.end(); 1957 | 1958 | while(it != itEnd) 1959 | { 1960 | itNext = it; 1961 | ++itNext; 1962 | 1963 | (*it)->emit(); 1964 | 1965 | it = itNext; 1966 | } 1967 | } 1968 | }; 1969 | 1970 | template 1971 | class signal1 : public _signal_base1 1972 | { 1973 | public: 1974 | signal1() 1975 | { 1976 | ; 1977 | } 1978 | 1979 | signal1(const signal1& s) 1980 | : _signal_base1(s) 1981 | { 1982 | ; 1983 | } 1984 | 1985 | template 1986 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type)) 1987 | { 1988 | lock_block lock(this); 1989 | _connection1* conn = 1990 | new _connection1(pclass, pmemfun); 1991 | m_connected_slots.push_back(conn); 1992 | pclass->signal_connect(this); 1993 | } 1994 | 1995 | void emit(arg1_type a1) 1996 | { 1997 | lock_block lock(this); 1998 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 1999 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2000 | 2001 | while(it != itEnd) 2002 | { 2003 | itNext = it; 2004 | ++itNext; 2005 | 2006 | (*it)->emit(a1); 2007 | 2008 | it = itNext; 2009 | } 2010 | } 2011 | 2012 | void operator()(arg1_type a1) 2013 | { 2014 | lock_block lock(this); 2015 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2016 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2017 | 2018 | while(it != itEnd) 2019 | { 2020 | itNext = it; 2021 | ++itNext; 2022 | 2023 | (*it)->emit(a1); 2024 | 2025 | it = itNext; 2026 | } 2027 | } 2028 | }; 2029 | 2030 | template 2031 | class signal2 : public _signal_base2 2032 | { 2033 | public: 2034 | signal2() 2035 | { 2036 | ; 2037 | } 2038 | 2039 | signal2(const signal2& s) 2040 | : _signal_base2(s) 2041 | { 2042 | ; 2043 | } 2044 | 2045 | template 2046 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2047 | arg2_type)) 2048 | { 2049 | lock_block lock(this); 2050 | _connection2* conn = new 2051 | _connection2(pclass, pmemfun); 2052 | m_connected_slots.push_back(conn); 2053 | pclass->signal_connect(this); 2054 | } 2055 | 2056 | void emit(arg1_type a1, arg2_type a2) 2057 | { 2058 | lock_block lock(this); 2059 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2060 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2061 | 2062 | while(it != itEnd) 2063 | { 2064 | itNext = it; 2065 | ++itNext; 2066 | 2067 | (*it)->emit(a1, a2); 2068 | 2069 | it = itNext; 2070 | } 2071 | } 2072 | 2073 | void operator()(arg1_type a1, arg2_type a2) 2074 | { 2075 | lock_block lock(this); 2076 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2077 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2078 | 2079 | while(it != itEnd) 2080 | { 2081 | itNext = it; 2082 | ++itNext; 2083 | 2084 | (*it)->emit(a1, a2); 2085 | 2086 | it = itNext; 2087 | } 2088 | } 2089 | }; 2090 | 2091 | template 2092 | class signal3 : public _signal_base3 2093 | { 2094 | public: 2095 | signal3() 2096 | { 2097 | ; 2098 | } 2099 | 2100 | signal3(const signal3& s) 2101 | : _signal_base3(s) 2102 | { 2103 | ; 2104 | } 2105 | 2106 | template 2107 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2108 | arg2_type, arg3_type)) 2109 | { 2110 | lock_block lock(this); 2111 | _connection3* conn = 2112 | new _connection3(pclass, 2113 | pmemfun); 2114 | m_connected_slots.push_back(conn); 2115 | pclass->signal_connect(this); 2116 | } 2117 | 2118 | void emit(arg1_type a1, arg2_type a2, arg3_type a3) 2119 | { 2120 | lock_block lock(this); 2121 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2122 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2123 | 2124 | while(it != itEnd) 2125 | { 2126 | itNext = it; 2127 | ++itNext; 2128 | 2129 | (*it)->emit(a1, a2, a3); 2130 | 2131 | it = itNext; 2132 | } 2133 | } 2134 | 2135 | void operator()(arg1_type a1, arg2_type a2, arg3_type a3) 2136 | { 2137 | lock_block lock(this); 2138 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2139 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2140 | 2141 | while(it != itEnd) 2142 | { 2143 | itNext = it; 2144 | ++itNext; 2145 | 2146 | (*it)->emit(a1, a2, a3); 2147 | 2148 | it = itNext; 2149 | } 2150 | } 2151 | }; 2152 | 2153 | template 2154 | class signal4 : public _signal_base4 2156 | { 2157 | public: 2158 | signal4() 2159 | { 2160 | ; 2161 | } 2162 | 2163 | signal4(const signal4& s) 2164 | : _signal_base4(s) 2165 | { 2166 | ; 2167 | } 2168 | 2169 | template 2170 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2171 | arg2_type, arg3_type, arg4_type)) 2172 | { 2173 | lock_block lock(this); 2174 | _connection4* 2175 | conn = new _connection4(pclass, pmemfun); 2177 | m_connected_slots.push_back(conn); 2178 | pclass->signal_connect(this); 2179 | } 2180 | 2181 | void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4) 2182 | { 2183 | lock_block lock(this); 2184 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2185 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2186 | 2187 | while(it != itEnd) 2188 | { 2189 | itNext = it; 2190 | ++itNext; 2191 | 2192 | (*it)->emit(a1, a2, a3, a4); 2193 | 2194 | it = itNext; 2195 | } 2196 | } 2197 | 2198 | void operator()(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4) 2199 | { 2200 | lock_block lock(this); 2201 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2202 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2203 | 2204 | while(it != itEnd) 2205 | { 2206 | itNext = it; 2207 | ++itNext; 2208 | 2209 | (*it)->emit(a1, a2, a3, a4); 2210 | 2211 | it = itNext; 2212 | } 2213 | } 2214 | }; 2215 | 2216 | template 2218 | class signal5 : public _signal_base5 2220 | { 2221 | public: 2222 | signal5() 2223 | { 2224 | ; 2225 | } 2226 | 2227 | signal5(const signal5& s) 2229 | : _signal_base5(s) 2231 | { 2232 | ; 2233 | } 2234 | 2235 | template 2236 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2237 | arg2_type, arg3_type, arg4_type, arg5_type)) 2238 | { 2239 | lock_block lock(this); 2240 | _connection5* conn = new _connection5(pclass, pmemfun); 2243 | m_connected_slots.push_back(conn); 2244 | pclass->signal_connect(this); 2245 | } 2246 | 2247 | void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2248 | arg5_type a5) 2249 | { 2250 | lock_block lock(this); 2251 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2252 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2253 | 2254 | while(it != itEnd) 2255 | { 2256 | itNext = it; 2257 | ++itNext; 2258 | 2259 | (*it)->emit(a1, a2, a3, a4, a5); 2260 | 2261 | it = itNext; 2262 | } 2263 | } 2264 | 2265 | void operator()(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2266 | arg5_type a5) 2267 | { 2268 | lock_block lock(this); 2269 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2270 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2271 | 2272 | while(it != itEnd) 2273 | { 2274 | itNext = it; 2275 | ++itNext; 2276 | 2277 | (*it)->emit(a1, a2, a3, a4, a5); 2278 | 2279 | it = itNext; 2280 | } 2281 | } 2282 | }; 2283 | 2284 | 2285 | template 2287 | class signal6 : public _signal_base6 2289 | { 2290 | public: 2291 | signal6() 2292 | { 2293 | ; 2294 | } 2295 | 2296 | signal6(const signal6& s) 2298 | : _signal_base6(s) 2300 | { 2301 | ; 2302 | } 2303 | 2304 | template 2305 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2306 | arg2_type, arg3_type, arg4_type, arg5_type, arg6_type)) 2307 | { 2308 | lock_block lock(this); 2309 | _connection6* conn = 2311 | new _connection6(pclass, pmemfun); 2313 | m_connected_slots.push_back(conn); 2314 | pclass->signal_connect(this); 2315 | } 2316 | 2317 | void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2318 | arg5_type a5, arg6_type a6) 2319 | { 2320 | lock_block lock(this); 2321 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2322 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2323 | 2324 | while(it != itEnd) 2325 | { 2326 | itNext = it; 2327 | ++itNext; 2328 | 2329 | (*it)->emit(a1, a2, a3, a4, a5, a6); 2330 | 2331 | it = itNext; 2332 | } 2333 | } 2334 | 2335 | void operator()(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2336 | arg5_type a5, arg6_type a6) 2337 | { 2338 | lock_block lock(this); 2339 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2340 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2341 | 2342 | while(it != itEnd) 2343 | { 2344 | itNext = it; 2345 | ++itNext; 2346 | 2347 | (*it)->emit(a1, a2, a3, a4, a5, a6); 2348 | 2349 | it = itNext; 2350 | } 2351 | } 2352 | }; 2353 | 2354 | template 2356 | class signal7 : public _signal_base7 2358 | { 2359 | public: 2360 | signal7() 2361 | { 2362 | ; 2363 | } 2364 | 2365 | signal7(const signal7& s) 2367 | : _signal_base7(s) 2369 | { 2370 | ; 2371 | } 2372 | 2373 | template 2374 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2375 | arg2_type, arg3_type, arg4_type, arg5_type, arg6_type, 2376 | arg7_type)) 2377 | { 2378 | lock_block lock(this); 2379 | _connection7* conn = 2381 | new _connection7(pclass, pmemfun); 2383 | m_connected_slots.push_back(conn); 2384 | pclass->signal_connect(this); 2385 | } 2386 | 2387 | void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2388 | arg5_type a5, arg6_type a6, arg7_type a7) 2389 | { 2390 | lock_block lock(this); 2391 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2392 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2393 | 2394 | while(it != itEnd) 2395 | { 2396 | itNext = it; 2397 | ++itNext; 2398 | 2399 | (*it)->emit(a1, a2, a3, a4, a5, a6, a7); 2400 | 2401 | it = itNext; 2402 | } 2403 | } 2404 | 2405 | void operator()(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2406 | arg5_type a5, arg6_type a6, arg7_type a7) 2407 | { 2408 | lock_block lock(this); 2409 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2410 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2411 | 2412 | while(it != itEnd) 2413 | { 2414 | itNext = it; 2415 | ++itNext; 2416 | 2417 | (*it)->emit(a1, a2, a3, a4, a5, a6, a7); 2418 | 2419 | it = itNext; 2420 | } 2421 | } 2422 | }; 2423 | 2424 | template 2426 | class signal8 : public _signal_base8 2428 | { 2429 | public: 2430 | signal8() 2431 | { 2432 | ; 2433 | } 2434 | 2435 | signal8(const signal8& s) 2437 | : _signal_base8(s) 2439 | { 2440 | ; 2441 | } 2442 | 2443 | template 2444 | void connect(desttype* pclass, void (desttype::*pmemfun)(arg1_type, 2445 | arg2_type, arg3_type, arg4_type, arg5_type, arg6_type, 2446 | arg7_type, arg8_type)) 2447 | { 2448 | lock_block lock(this); 2449 | _connection8* conn = 2451 | new _connection8(pclass, pmemfun); 2454 | m_connected_slots.push_back(conn); 2455 | pclass->signal_connect(this); 2456 | } 2457 | 2458 | void emit(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2459 | arg5_type a5, arg6_type a6, arg7_type a7, arg8_type a8) 2460 | { 2461 | lock_block lock(this); 2462 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2463 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2464 | 2465 | while(it != itEnd) 2466 | { 2467 | itNext = it; 2468 | ++itNext; 2469 | 2470 | (*it)->emit(a1, a2, a3, a4, a5, a6, a7, a8); 2471 | 2472 | it = itNext; 2473 | } 2474 | } 2475 | 2476 | void operator()(arg1_type a1, arg2_type a2, arg3_type a3, arg4_type a4, 2477 | arg5_type a5, arg6_type a6, arg7_type a7, arg8_type a8) 2478 | { 2479 | lock_block lock(this); 2480 | connections_list::const_iterator itNext, it = m_connected_slots.begin(); 2481 | connections_list::const_iterator itEnd = m_connected_slots.end(); 2482 | 2483 | while(it != itEnd) 2484 | { 2485 | itNext = it; 2486 | ++itNext; 2487 | 2488 | (*it)->emit(a1, a2, a3, a4, a5, a6, a7, a8); 2489 | 2490 | it = itNext; 2491 | } 2492 | } 2493 | }; 2494 | 2495 | }; // namespace sigslot 2496 | 2497 | #endif // SIGSLOT_H__ 2498 | 2499 | -------------------------------------------------------------------------------- /src/pugiconfig.hpp: -------------------------------------------------------------------------------- 1 | /** 2 | * pugixml parser - version 1.0 3 | * -------------------------------------------------------- 4 | * Copyright (C) 2006-2010, by Arseny Kapoulkine (arseny.kapoulkine@gmail.com) 5 | * Report bugs and download new versions at http://pugixml.org/ 6 | * 7 | * This library is distributed under the MIT License. See notice at the end 8 | * of this file. 9 | * 10 | * This work is based on the pugxml parser, which is: 11 | * Copyright (C) 2003, by Kristen Wegner (kristen@tima.net) 12 | */ 13 | 14 | #ifndef HEADER_PUGICONFIG_HPP 15 | #define HEADER_PUGICONFIG_HPP 16 | 17 | // Uncomment this to enable wchar_t mode 18 | // #define PUGIXML_WCHAR_MODE 19 | 20 | // Uncomment this to disable XPath 21 | // #define PUGIXML_NO_XPATH 22 | 23 | // Uncomment this to disable STL 24 | // Note: you can't use XPath with PUGIXML_NO_STL 25 | // #define PUGIXML_NO_STL 26 | 27 | // Uncomment this to disable exceptions 28 | // Note: you can't use XPath with PUGIXML_NO_EXCEPTIONS 29 | // #define PUGIXML_NO_EXCEPTIONS 30 | 31 | // Set this to control attributes for public classes/functions, i.e.: 32 | // #define PUGIXML_API __declspec(dllexport) // to export all public symbols from DLL 33 | // #define PUGIXML_CLASS __declspec(dllimport) // to import all classes from DLL 34 | // #define PUGIXML_FUNCTION __fastcall // to set calling conventions to all public functions to fastcall 35 | // In absence of PUGIXML_CLASS/PUGIXML_FUNCTION definitions PUGIXML_API is used instead 36 | 37 | #endif 38 | 39 | /** 40 | * Copyright (c) 2006-2010 Arseny Kapoulkine 41 | * 42 | * Permission is hereby granted, free of charge, to any person 43 | * obtaining a copy of this software and associated documentation 44 | * files (the "Software"), to deal in the Software without 45 | * restriction, including without limitation the rights to use, 46 | * copy, modify, merge, publish, distribute, sublicense, and/or sell 47 | * copies of the Software, and to permit persons to whom the 48 | * Software is furnished to do so, subject to the following 49 | * conditions: 50 | * 51 | * The above copyright notice and this permission notice shall be 52 | * included in all copies or substantial portions of the Software. 53 | * 54 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, 55 | * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES 56 | * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND 57 | * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT 58 | * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, 59 | * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING 60 | * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR 61 | * OTHER DEALINGS IN THE SOFTWARE. 62 | */ 63 | -------------------------------------------------------------------------------- /src/pugixml.hpp: -------------------------------------------------------------------------------- 1 | /** 2 | * pugixml parser - version 1.0 3 | * -------------------------------------------------------- 4 | * Copyright (C) 2006-2010, by Arseny Kapoulkine (arseny.kapoulkine@gmail.com) 5 | * Report bugs and download new versions at http://pugixml.org/ 6 | * 7 | * This library is distributed under the MIT License. See notice at the end 8 | * of this file. 9 | * 10 | * This work is based on the pugxml parser, which is: 11 | * Copyright (C) 2003, by Kristen Wegner (kristen@tima.net) 12 | */ 13 | 14 | #ifndef HEADER_PUGIXML_HPP 15 | #define HEADER_PUGIXML_HPP 16 | 17 | #include "pugiconfig.hpp" 18 | 19 | #ifndef PUGIXML_NO_STL 20 | namespace std 21 | { 22 | struct bidirectional_iterator_tag; 23 | 24 | #ifdef __SUNPRO_CC 25 | // Sun C++ compiler has a bug which forces template argument names in forward declarations to be the same as in actual definitions 26 | template class allocator; 27 | template struct char_traits; 28 | template class basic_istream; 29 | template class basic_ostream; 30 | template class basic_string; 31 | #else 32 | // Borland C++ compiler has a bug which forces template argument names in forward declarations to be the same as in actual definitions 33 | template class allocator; 34 | template struct char_traits; 35 | template class basic_istream; 36 | template class basic_ostream; 37 | template class basic_string; 38 | #endif 39 | 40 | // Digital Mars compiler has a bug which requires a forward declaration for explicit instantiation (otherwise type selection is messed up later, producing link errors) 41 | // Also note that we have to declare char_traits as a class here, since it's defined that way 42 | #ifdef __DMC__ 43 | template <> class char_traits; 44 | #endif 45 | } 46 | #endif 47 | 48 | // Macro for deprecated features 49 | #ifndef PUGIXML_DEPRECATED 50 | # if defined(__GNUC__) 51 | # define PUGIXML_DEPRECATED __attribute__((deprecated)) 52 | # elif defined(_MSC_VER) && _MSC_VER >= 1300 53 | # define PUGIXML_DEPRECATED __declspec(deprecated) 54 | # else 55 | # define PUGIXML_DEPRECATED 56 | # endif 57 | #endif 58 | 59 | // Include exception header for XPath 60 | #if !defined(PUGIXML_NO_XPATH) && !defined(PUGIXML_NO_EXCEPTIONS) 61 | # include 62 | #endif 63 | 64 | // If no API is defined, assume default 65 | #ifndef PUGIXML_API 66 | # define PUGIXML_API 67 | #endif 68 | 69 | // If no API for classes is defined, assume default 70 | #ifndef PUGIXML_CLASS 71 | # define PUGIXML_CLASS PUGIXML_API 72 | #endif 73 | 74 | // If no API for functions is defined, assume default 75 | #ifndef PUGIXML_FUNCTION 76 | # define PUGIXML_FUNCTION PUGIXML_API 77 | #endif 78 | 79 | #include 80 | 81 | // Character interface macros 82 | #ifdef PUGIXML_WCHAR_MODE 83 | # define PUGIXML_TEXT(t) L ## t 84 | # define PUGIXML_CHAR wchar_t 85 | #else 86 | # define PUGIXML_TEXT(t) t 87 | # define PUGIXML_CHAR char 88 | #endif 89 | 90 | namespace pugi 91 | { 92 | // Character type used for all internal storage and operations; depends on PUGIXML_WCHAR_MODE 93 | typedef PUGIXML_CHAR char_t; 94 | 95 | #ifndef PUGIXML_NO_STL 96 | // String type used for operations that work with STL string; depends on PUGIXML_WCHAR_MODE 97 | typedef std::basic_string, std::allocator > string_t; 98 | #endif 99 | } 100 | 101 | // The PugiXML namespace 102 | namespace pugi 103 | { 104 | // Tree node types 105 | enum xml_node_type 106 | { 107 | node_null, // Empty (null) node handle 108 | node_document, // A document tree's absolute root 109 | node_element, // Element tag, i.e. '' 110 | node_pcdata, // Plain character data, i.e. 'text' 111 | node_cdata, // Character data, i.e. '' 112 | node_comment, // Comment tag, i.e. '' 113 | node_pi, // Processing instruction, i.e. '' 114 | node_declaration, // Document declaration, i.e. '' 115 | node_doctype // Document type declaration, i.e. '' 116 | }; 117 | 118 | // Parsing options 119 | 120 | // Minimal parsing mode (equivalent to turning all other flags off). 121 | // Only elements and PCDATA sections are added to the DOM tree, no text conversions are performed. 122 | const unsigned int parse_minimal = 0x0000; 123 | 124 | // This flag determines if processing instructions (node_pi) are added to the DOM tree. This flag is off by default. 125 | const unsigned int parse_pi = 0x0001; 126 | 127 | // This flag determines if comments (node_comment) are added to the DOM tree. This flag is off by default. 128 | const unsigned int parse_comments = 0x0002; 129 | 130 | // This flag determines if CDATA sections (node_cdata) are added to the DOM tree. This flag is on by default. 131 | const unsigned int parse_cdata = 0x0004; 132 | 133 | // This flag determines if plain character data (node_pcdata) that consist only of whitespace are added to the DOM tree. 134 | // This flag is off by default; turning it on usually results in slower parsing and more memory consumption. 135 | const unsigned int parse_ws_pcdata = 0x0008; 136 | 137 | // This flag determines if character and entity references are expanded during parsing. This flag is on by default. 138 | const unsigned int parse_escapes = 0x0010; 139 | 140 | // This flag determines if EOL characters are normalized (converted to #xA) during parsing. This flag is on by default. 141 | const unsigned int parse_eol = 0x0020; 142 | 143 | // This flag determines if attribute values are normalized using CDATA normalization rules during parsing. This flag is on by default. 144 | const unsigned int parse_wconv_attribute = 0x0040; 145 | 146 | // This flag determines if attribute values are normalized using NMTOKENS normalization rules during parsing. This flag is off by default. 147 | const unsigned int parse_wnorm_attribute = 0x0080; 148 | 149 | // This flag determines if document declaration (node_declaration) is added to the DOM tree. This flag is off by default. 150 | const unsigned int parse_declaration = 0x0100; 151 | 152 | // This flag determines if document type declaration (node_doctype) is added to the DOM tree. This flag is off by default. 153 | const unsigned int parse_doctype = 0x0200; 154 | 155 | // The default parsing mode. 156 | // Elements, PCDATA and CDATA sections are added to the DOM tree, character/reference entities are expanded, 157 | // End-of-Line characters are normalized, attribute values are normalized using CDATA normalization rules. 158 | const unsigned int parse_default = parse_cdata | parse_escapes | parse_wconv_attribute | parse_eol; 159 | 160 | // The full parsing mode. 161 | // Nodes of all types are added to the DOM tree, character/reference entities are expanded, 162 | // End-of-Line characters are normalized, attribute values are normalized using CDATA normalization rules. 163 | const unsigned int parse_full = parse_default | parse_pi | parse_comments | parse_declaration | parse_doctype; 164 | 165 | // These flags determine the encoding of input data for XML document 166 | enum xml_encoding 167 | { 168 | encoding_auto, // Auto-detect input encoding using BOM or < / >& stream); 245 | xml_writer_stream(std::basic_ostream >& stream); 246 | 247 | virtual void write(const void* data, size_t size); 248 | 249 | private: 250 | std::basic_ostream >* narrow_stream; 251 | std::basic_ostream >* wide_stream; 252 | }; 253 | #endif 254 | 255 | // A light-weight handle for manipulating attributes in DOM tree 256 | class PUGIXML_CLASS xml_attribute 257 | { 258 | friend class xml_attribute_iterator; 259 | friend class xml_node; 260 | 261 | private: 262 | xml_attribute_struct* _attr; 263 | 264 | typedef xml_attribute_struct* xml_attribute::*unspecified_bool_type; 265 | 266 | public: 267 | // Default constructor. Constructs an empty attribute. 268 | xml_attribute(); 269 | 270 | // Constructs attribute from internal pointer 271 | explicit xml_attribute(xml_attribute_struct* attr); 272 | 273 | // Safe bool conversion operator 274 | operator unspecified_bool_type() const; 275 | 276 | // Borland C++ workaround 277 | bool operator!() const; 278 | 279 | // Comparison operators (compares wrapped attribute pointers) 280 | bool operator==(const xml_attribute& r) const; 281 | bool operator!=(const xml_attribute& r) const; 282 | bool operator<(const xml_attribute& r) const; 283 | bool operator>(const xml_attribute& r) const; 284 | bool operator<=(const xml_attribute& r) const; 285 | bool operator>=(const xml_attribute& r) const; 286 | 287 | // Check if attribute is empty 288 | bool empty() const; 289 | 290 | // Get attribute name/value, or "" if attribute is empty 291 | const char_t* name() const; 292 | const char_t* value() const; 293 | 294 | // Get attribute value as a number, or 0 if conversion did not succeed or attribute is empty 295 | int as_int() const; 296 | unsigned int as_uint() const; 297 | double as_double() const; 298 | float as_float() const; 299 | 300 | // Get attribute value as bool (returns true if first character is in '1tTyY' set), or false if attribute is empty 301 | bool as_bool() const; 302 | 303 | // Set attribute name/value (returns false if attribute is empty or there is not enough memory) 304 | bool set_name(const char_t* rhs); 305 | bool set_value(const char_t* rhs); 306 | 307 | // Set attribute value with type conversion (numbers are converted to strings, boolean is converted to "true"/"false") 308 | bool set_value(int rhs); 309 | bool set_value(unsigned int rhs); 310 | bool set_value(double rhs); 311 | bool set_value(bool rhs); 312 | 313 | // Set attribute value (equivalent to set_value without error checking) 314 | xml_attribute& operator=(const char_t* rhs); 315 | xml_attribute& operator=(int rhs); 316 | xml_attribute& operator=(unsigned int rhs); 317 | xml_attribute& operator=(double rhs); 318 | xml_attribute& operator=(bool rhs); 319 | 320 | // Get next/previous attribute in the attribute list of the parent node 321 | xml_attribute next_attribute() const; 322 | xml_attribute previous_attribute() const; 323 | 324 | // Get hash value (unique for handles to the same object) 325 | size_t hash_value() const; 326 | 327 | // Get internal pointer 328 | xml_attribute_struct* internal_object() const; 329 | }; 330 | 331 | #ifdef __BORLANDC__ 332 | // Borland C++ workaround 333 | bool PUGIXML_FUNCTION operator&&(const xml_attribute& lhs, bool rhs); 334 | bool PUGIXML_FUNCTION operator||(const xml_attribute& lhs, bool rhs); 335 | #endif 336 | 337 | // A light-weight handle for manipulating nodes in DOM tree 338 | class PUGIXML_CLASS xml_node 339 | { 340 | friend class xml_attribute_iterator; 341 | friend class xml_node_iterator; 342 | 343 | protected: 344 | xml_node_struct* _root; 345 | 346 | typedef xml_node_struct* xml_node::*unspecified_bool_type; 347 | 348 | public: 349 | // Default constructor. Constructs an empty node. 350 | xml_node(); 351 | 352 | // Constructs node from internal pointer 353 | explicit xml_node(xml_node_struct* p); 354 | 355 | // Safe bool conversion operator 356 | operator unspecified_bool_type() const; 357 | 358 | // Borland C++ workaround 359 | bool operator!() const; 360 | 361 | // Comparison operators (compares wrapped node pointers) 362 | bool operator==(const xml_node& r) const; 363 | bool operator!=(const xml_node& r) const; 364 | bool operator<(const xml_node& r) const; 365 | bool operator>(const xml_node& r) const; 366 | bool operator<=(const xml_node& r) const; 367 | bool operator>=(const xml_node& r) const; 368 | 369 | // Check if node is empty. 370 | bool empty() const; 371 | 372 | // Get node type 373 | xml_node_type type() const; 374 | 375 | // Get node name/value, or "" if node is empty or it has no name/value 376 | const char_t* name() const; 377 | const char_t* value() const; 378 | 379 | // Get attribute list 380 | xml_attribute first_attribute() const; 381 | xml_attribute last_attribute() const; 382 | 383 | // Get children list 384 | xml_node first_child() const; 385 | xml_node last_child() const; 386 | 387 | // Get next/previous sibling in the children list of the parent node 388 | xml_node next_sibling() const; 389 | xml_node previous_sibling() const; 390 | 391 | // Get parent node 392 | xml_node parent() const; 393 | 394 | // Get root of DOM tree this node belongs to 395 | xml_node root() const; 396 | 397 | // Get child, attribute or next/previous sibling with the specified name 398 | xml_node child(const char_t* name) const; 399 | xml_attribute attribute(const char_t* name) const; 400 | xml_node next_sibling(const char_t* name) const; 401 | xml_node previous_sibling(const char_t* name) const; 402 | 403 | // Get child value of current node; that is, value of the first child node of type PCDATA/CDATA 404 | const char_t* child_value() const; 405 | 406 | // Get child value of child with specified name. Equivalent to child(name).child_value(). 407 | const char_t* child_value(const char_t* name) const; 408 | 409 | // Set node name/value (returns false if node is empty, there is not enough memory, or node can not have name/value) 410 | bool set_name(const char_t* rhs); 411 | bool set_value(const char_t* rhs); 412 | 413 | // Add attribute with specified name. Returns added attribute, or empty attribute on errors. 414 | xml_attribute append_attribute(const char_t* name); 415 | xml_attribute prepend_attribute(const char_t* name); 416 | xml_attribute insert_attribute_after(const char_t* name, const xml_attribute& attr); 417 | xml_attribute insert_attribute_before(const char_t* name, const xml_attribute& attr); 418 | 419 | // Add a copy of the specified attribute. Returns added attribute, or empty attribute on errors. 420 | xml_attribute append_copy(const xml_attribute& proto); 421 | xml_attribute prepend_copy(const xml_attribute& proto); 422 | xml_attribute insert_copy_after(const xml_attribute& proto, const xml_attribute& attr); 423 | xml_attribute insert_copy_before(const xml_attribute& proto, const xml_attribute& attr); 424 | 425 | // Add child node with specified type. Returns added node, or empty node on errors. 426 | xml_node append_child(xml_node_type type = node_element); 427 | xml_node prepend_child(xml_node_type type = node_element); 428 | xml_node insert_child_after(xml_node_type type, const xml_node& node); 429 | xml_node insert_child_before(xml_node_type type, const xml_node& node); 430 | 431 | // Add child element with specified name. Returns added node, or empty node on errors. 432 | xml_node append_child(const char_t* name); 433 | xml_node prepend_child(const char_t* name); 434 | xml_node insert_child_after(const char_t* name, const xml_node& node); 435 | xml_node insert_child_before(const char_t* name, const xml_node& node); 436 | 437 | // Add a copy of the specified node as a child. Returns added node, or empty node on errors. 438 | xml_node append_copy(const xml_node& proto); 439 | xml_node prepend_copy(const xml_node& proto); 440 | xml_node insert_copy_after(const xml_node& proto, const xml_node& node); 441 | xml_node insert_copy_before(const xml_node& proto, const xml_node& node); 442 | 443 | // Remove specified attribute 444 | bool remove_attribute(const xml_attribute& a); 445 | bool remove_attribute(const char_t* name); 446 | 447 | // Remove specified child 448 | bool remove_child(const xml_node& n); 449 | bool remove_child(const char_t* name); 450 | 451 | // Find attribute using predicate. Returns first attribute for which predicate returned true. 452 | template xml_attribute find_attribute(Predicate pred) const 453 | { 454 | if (!_root) return xml_attribute(); 455 | 456 | for (xml_attribute attrib = first_attribute(); attrib; attrib = attrib.next_attribute()) 457 | if (pred(attrib)) 458 | return attrib; 459 | 460 | return xml_attribute(); 461 | } 462 | 463 | // Find child node using predicate. Returns first child for which predicate returned true. 464 | template xml_node find_child(Predicate pred) const 465 | { 466 | if (!_root) return xml_node(); 467 | 468 | for (xml_node node = first_child(); node; node = node.next_sibling()) 469 | if (pred(node)) 470 | return node; 471 | 472 | return xml_node(); 473 | } 474 | 475 | // Find node from subtree using predicate. Returns first node from subtree (depth-first), for which predicate returned true. 476 | template xml_node find_node(Predicate pred) const 477 | { 478 | if (!_root) return xml_node(); 479 | 480 | xml_node cur = first_child(); 481 | 482 | while (cur._root && cur._root != _root) 483 | { 484 | if (pred(cur)) return cur; 485 | 486 | if (cur.first_child()) cur = cur.first_child(); 487 | else if (cur.next_sibling()) cur = cur.next_sibling(); 488 | else 489 | { 490 | while (!cur.next_sibling() && cur._root != _root) cur = cur.parent(); 491 | 492 | if (cur._root != _root) cur = cur.next_sibling(); 493 | } 494 | } 495 | 496 | return xml_node(); 497 | } 498 | 499 | // Find child node by attribute name/value 500 | xml_node find_child_by_attribute(const char_t* name, const char_t* attr_name, const char_t* attr_value) const; 501 | xml_node find_child_by_attribute(const char_t* attr_name, const char_t* attr_value) const; 502 | 503 | #ifndef PUGIXML_NO_STL 504 | // Get the absolute node path from root as a text string. 505 | string_t path(char_t delimiter = '/') const; 506 | #endif 507 | 508 | // Search for a node by path consisting of node names and . or .. elements. 509 | xml_node first_element_by_path(const char_t* path, char_t delimiter = '/') const; 510 | 511 | // Recursively traverse subtree with xml_tree_walker 512 | bool traverse(xml_tree_walker& walker); 513 | 514 | #ifndef PUGIXML_NO_XPATH 515 | // Select single node by evaluating XPath query. Returns first node from the resulting node set. 516 | xpath_node select_single_node(const char_t* query, xpath_variable_set* variables = 0) const; 517 | xpath_node select_single_node(const xpath_query& query) const; 518 | 519 | // Select node set by evaluating XPath query 520 | xpath_node_set select_nodes(const char_t* query, xpath_variable_set* variables = 0) const; 521 | xpath_node_set select_nodes(const xpath_query& query) const; 522 | #endif 523 | 524 | // Print subtree using a writer object 525 | void print(xml_writer& writer, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, xml_encoding encoding = encoding_auto, unsigned int depth = 0) const; 526 | 527 | #ifndef PUGIXML_NO_STL 528 | // Print subtree to stream 529 | void print(std::basic_ostream >& os, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, xml_encoding encoding = encoding_auto, unsigned int depth = 0) const; 530 | void print(std::basic_ostream >& os, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, unsigned int depth = 0) const; 531 | #endif 532 | 533 | // Child nodes iterators 534 | typedef xml_node_iterator iterator; 535 | 536 | iterator begin() const; 537 | iterator end() const; 538 | 539 | // Attribute iterators 540 | typedef xml_attribute_iterator attribute_iterator; 541 | 542 | attribute_iterator attributes_begin() const; 543 | attribute_iterator attributes_end() const; 544 | 545 | // Get node offset in parsed file/string (in char_t units) for debugging purposes 546 | ptrdiff_t offset_debug() const; 547 | 548 | // Get hash value (unique for handles to the same object) 549 | size_t hash_value() const; 550 | 551 | // Get internal pointer 552 | xml_node_struct* internal_object() const; 553 | }; 554 | 555 | #ifdef __BORLANDC__ 556 | // Borland C++ workaround 557 | bool PUGIXML_FUNCTION operator&&(const xml_node& lhs, bool rhs); 558 | bool PUGIXML_FUNCTION operator||(const xml_node& lhs, bool rhs); 559 | #endif 560 | 561 | // Child node iterator (a bidirectional iterator over a collection of xml_node) 562 | class PUGIXML_CLASS xml_node_iterator 563 | { 564 | friend class xml_node; 565 | 566 | private: 567 | xml_node _wrap; 568 | xml_node _parent; 569 | 570 | xml_node_iterator(xml_node_struct* ref, xml_node_struct* parent); 571 | 572 | public: 573 | // Iterator traits 574 | typedef ptrdiff_t difference_type; 575 | typedef xml_node value_type; 576 | typedef xml_node* pointer; 577 | typedef xml_node& reference; 578 | 579 | #ifndef PUGIXML_NO_STL 580 | typedef std::bidirectional_iterator_tag iterator_category; 581 | #endif 582 | 583 | // Default constructor 584 | xml_node_iterator(); 585 | 586 | // Construct an iterator which points to the specified node 587 | xml_node_iterator(const xml_node& node); 588 | 589 | // Iterator operators 590 | bool operator==(const xml_node_iterator& rhs) const; 591 | bool operator!=(const xml_node_iterator& rhs) const; 592 | 593 | xml_node& operator*(); 594 | xml_node* operator->(); 595 | 596 | const xml_node_iterator& operator++(); 597 | xml_node_iterator operator++(int); 598 | 599 | const xml_node_iterator& operator--(); 600 | xml_node_iterator operator--(int); 601 | }; 602 | 603 | // Attribute iterator (a bidirectional iterator over a collection of xml_attribute) 604 | class PUGIXML_CLASS xml_attribute_iterator 605 | { 606 | friend class xml_node; 607 | 608 | private: 609 | xml_attribute _wrap; 610 | xml_node _parent; 611 | 612 | xml_attribute_iterator(xml_attribute_struct* ref, xml_node_struct* parent); 613 | 614 | public: 615 | // Iterator traits 616 | typedef ptrdiff_t difference_type; 617 | typedef xml_attribute value_type; 618 | typedef xml_attribute* pointer; 619 | typedef xml_attribute& reference; 620 | 621 | #ifndef PUGIXML_NO_STL 622 | typedef std::bidirectional_iterator_tag iterator_category; 623 | #endif 624 | 625 | // Default constructor 626 | xml_attribute_iterator(); 627 | 628 | // Construct an iterator which points to the specified attribute 629 | xml_attribute_iterator(const xml_attribute& attr, const xml_node& parent); 630 | 631 | // Iterator operators 632 | bool operator==(const xml_attribute_iterator& rhs) const; 633 | bool operator!=(const xml_attribute_iterator& rhs) const; 634 | 635 | xml_attribute& operator*(); 636 | xml_attribute* operator->(); 637 | 638 | const xml_attribute_iterator& operator++(); 639 | xml_attribute_iterator operator++(int); 640 | 641 | const xml_attribute_iterator& operator--(); 642 | xml_attribute_iterator operator--(int); 643 | }; 644 | 645 | // Abstract tree walker class (see xml_node::traverse) 646 | class PUGIXML_CLASS xml_tree_walker 647 | { 648 | friend class xml_node; 649 | 650 | private: 651 | int _depth; 652 | 653 | protected: 654 | // Get current traversal depth 655 | int depth() const; 656 | 657 | public: 658 | xml_tree_walker(); 659 | virtual ~xml_tree_walker(); 660 | 661 | // Callback that is called when traversal begins 662 | virtual bool begin(xml_node& node); 663 | 664 | // Callback that is called for each node traversed 665 | virtual bool for_each(xml_node& node) = 0; 666 | 667 | // Callback that is called when traversal ends 668 | virtual bool end(xml_node& node); 669 | }; 670 | 671 | // Parsing status, returned as part of xml_parse_result object 672 | enum xml_parse_status 673 | { 674 | status_ok = 0, // No error 675 | 676 | status_file_not_found, // File was not found during load_file() 677 | status_io_error, // Error reading from file/stream 678 | status_out_of_memory, // Could not allocate memory 679 | status_internal_error, // Internal error occurred 680 | 681 | status_unrecognized_tag, // Parser could not determine tag type 682 | 683 | status_bad_pi, // Parsing error occurred while parsing document declaration/processing instruction 684 | status_bad_comment, // Parsing error occurred while parsing comment 685 | status_bad_cdata, // Parsing error occurred while parsing CDATA section 686 | status_bad_doctype, // Parsing error occurred while parsing document type declaration 687 | status_bad_pcdata, // Parsing error occurred while parsing PCDATA section 688 | status_bad_start_element, // Parsing error occurred while parsing start element tag 689 | status_bad_attribute, // Parsing error occurred while parsing element attribute 690 | status_bad_end_element, // Parsing error occurred while parsing end element tag 691 | status_end_element_mismatch // There was a mismatch of start-end tags (closing tag had incorrect name, some tag was not closed or there was an excessive closing tag) 692 | }; 693 | 694 | // Parsing result 695 | struct PUGIXML_CLASS xml_parse_result 696 | { 697 | // Parsing status (see xml_parse_status) 698 | xml_parse_status status; 699 | 700 | // Last parsed offset (in char_t units from start of input data) 701 | ptrdiff_t offset; 702 | 703 | // Source document encoding 704 | xml_encoding encoding; 705 | 706 | // Default constructor, initializes object to failed state 707 | xml_parse_result(); 708 | 709 | // Cast to bool operator 710 | operator bool() const; 711 | 712 | // Get error description 713 | const char* description() const; 714 | }; 715 | 716 | // Document class (DOM tree root) 717 | class PUGIXML_CLASS xml_document: public xml_node 718 | { 719 | private: 720 | char_t* _buffer; 721 | 722 | char _memory[192]; 723 | 724 | // Non-copyable semantics 725 | xml_document(const xml_document&); 726 | const xml_document& operator=(const xml_document&); 727 | 728 | void create(); 729 | void destroy(); 730 | 731 | xml_parse_result load_buffer_impl(void* contents, size_t size, unsigned int options, xml_encoding encoding, bool is_mutable, bool own); 732 | 733 | public: 734 | // Default constructor, makes empty document 735 | xml_document(); 736 | 737 | // Destructor, invalidates all node/attribute handles to this document 738 | ~xml_document(); 739 | 740 | // Removes all nodes, leaving the empty document 741 | void reset(); 742 | 743 | // Removes all nodes, then copies the entire contents of the specified document 744 | void reset(const xml_document& proto); 745 | 746 | #ifndef PUGIXML_NO_STL 747 | // Load document from stream. 748 | xml_parse_result load(std::basic_istream >& stream, unsigned int options = parse_default, xml_encoding encoding = encoding_auto); 749 | xml_parse_result load(std::basic_istream >& stream, unsigned int options = parse_default); 750 | #endif 751 | 752 | // Load document from zero-terminated string. No encoding conversions are applied. 753 | xml_parse_result load(const char_t* contents, unsigned int options = parse_default); 754 | 755 | // Load document from file 756 | xml_parse_result load_file(const char* path, unsigned int options = parse_default, xml_encoding encoding = encoding_auto); 757 | xml_parse_result load_file(const wchar_t* path, unsigned int options = parse_default, xml_encoding encoding = encoding_auto); 758 | 759 | // Load document from buffer. Copies/converts the buffer, so it may be deleted or changed after the function returns. 760 | xml_parse_result load_buffer(const void* contents, size_t size, unsigned int options = parse_default, xml_encoding encoding = encoding_auto); 761 | 762 | // Load document from buffer, using the buffer for in-place parsing (the buffer is modified and used for storage of document data). 763 | // You should ensure that buffer data will persist throughout the document's lifetime, and free the buffer memory manually once document is destroyed. 764 | xml_parse_result load_buffer_inplace(void* contents, size_t size, unsigned int options = parse_default, xml_encoding encoding = encoding_auto); 765 | 766 | // Load document from buffer, using the buffer for in-place parsing (the buffer is modified and used for storage of document data). 767 | // You should allocate the buffer with pugixml allocation function; document will free the buffer when it is no longer needed (you can't use it anymore). 768 | xml_parse_result load_buffer_inplace_own(void* contents, size_t size, unsigned int options = parse_default, xml_encoding encoding = encoding_auto); 769 | 770 | // Save XML document to writer (semantics is slightly different from xml_node::print, see documentation for details). 771 | void save(xml_writer& writer, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, xml_encoding encoding = encoding_auto) const; 772 | 773 | #ifndef PUGIXML_NO_STL 774 | // Save XML document to stream (semantics is slightly different from xml_node::print, see documentation for details). 775 | void save(std::basic_ostream >& stream, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, xml_encoding encoding = encoding_auto) const; 776 | void save(std::basic_ostream >& stream, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default) const; 777 | #endif 778 | 779 | // Save XML to file 780 | bool save_file(const char* path, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, xml_encoding encoding = encoding_auto) const; 781 | bool save_file(const wchar_t* path, const char_t* indent = PUGIXML_TEXT("\t"), unsigned int flags = format_default, xml_encoding encoding = encoding_auto) const; 782 | 783 | // Get document element 784 | xml_node document_element() const; 785 | }; 786 | 787 | #ifndef PUGIXML_NO_XPATH 788 | // XPath query return type 789 | enum xpath_value_type 790 | { 791 | xpath_type_none, // Unknown type (query failed to compile) 792 | xpath_type_node_set, // Node set (xpath_node_set) 793 | xpath_type_number, // Number 794 | xpath_type_string, // String 795 | xpath_type_boolean // Boolean 796 | }; 797 | 798 | // XPath parsing result 799 | struct PUGIXML_CLASS xpath_parse_result 800 | { 801 | // Error message (0 if no error) 802 | const char* error; 803 | 804 | // Last parsed offset (in char_t units from string start) 805 | ptrdiff_t offset; 806 | 807 | // Default constructor, initializes object to failed state 808 | xpath_parse_result(); 809 | 810 | // Cast to bool operator 811 | operator bool() const; 812 | 813 | // Get error description 814 | const char* description() const; 815 | }; 816 | 817 | // A single XPath variable 818 | class PUGIXML_CLASS xpath_variable 819 | { 820 | friend class xpath_variable_set; 821 | 822 | protected: 823 | xpath_value_type _type; 824 | xpath_variable* _next; 825 | 826 | xpath_variable(); 827 | 828 | // Non-copyable semantics 829 | xpath_variable(const xpath_variable&); 830 | xpath_variable& operator=(const xpath_variable&); 831 | 832 | public: 833 | // Get variable name 834 | const char_t* name() const; 835 | 836 | // Get variable type 837 | xpath_value_type type() const; 838 | 839 | // Get variable value; no type conversion is performed, default value (false, NaN, empty string, empty node set) is returned on type mismatch error 840 | bool get_boolean() const; 841 | double get_number() const; 842 | const char_t* get_string() const; 843 | const xpath_node_set& get_node_set() const; 844 | 845 | // Set variable value; no type conversion is performed, false is returned on type mismatch error 846 | bool set(bool value); 847 | bool set(double value); 848 | bool set(const char_t* value); 849 | bool set(const xpath_node_set& value); 850 | }; 851 | 852 | // A set of XPath variables 853 | class PUGIXML_CLASS xpath_variable_set 854 | { 855 | private: 856 | xpath_variable* _data[64]; 857 | 858 | // Non-copyable semantics 859 | xpath_variable_set(const xpath_variable_set&); 860 | xpath_variable_set& operator=(const xpath_variable_set&); 861 | 862 | xpath_variable* find(const char_t* name) const; 863 | 864 | public: 865 | // Default constructor/destructor 866 | xpath_variable_set(); 867 | ~xpath_variable_set(); 868 | 869 | // Add a new variable or get the existing one, if the types match 870 | xpath_variable* add(const char_t* name, xpath_value_type type); 871 | 872 | // Set value of an existing variable; no type conversion is performed, false is returned if there is no such variable or if types mismatch 873 | bool set(const char_t* name, bool value); 874 | bool set(const char_t* name, double value); 875 | bool set(const char_t* name, const char_t* value); 876 | bool set(const char_t* name, const xpath_node_set& value); 877 | 878 | // Get existing variable by name 879 | xpath_variable* get(const char_t* name); 880 | const xpath_variable* get(const char_t* name) const; 881 | }; 882 | 883 | // A compiled XPath query object 884 | class PUGIXML_CLASS xpath_query 885 | { 886 | private: 887 | void* _impl; 888 | xpath_parse_result _result; 889 | 890 | typedef void* xpath_query::*unspecified_bool_type; 891 | 892 | // Non-copyable semantics 893 | xpath_query(const xpath_query&); 894 | xpath_query& operator=(const xpath_query&); 895 | 896 | public: 897 | // Construct a compiled object from XPath expression. 898 | // If PUGIXML_NO_EXCEPTIONS is not defined, throws xpath_exception on compilation errors. 899 | explicit xpath_query(const char_t* query, xpath_variable_set* variables = 0); 900 | 901 | // Destructor 902 | ~xpath_query(); 903 | 904 | // Get query expression return type 905 | xpath_value_type return_type() const; 906 | 907 | // Evaluate expression as boolean value in the specified context; performs type conversion if necessary. 908 | // If PUGIXML_NO_EXCEPTIONS is not defined, throws std::bad_alloc on out of memory errors. 909 | bool evaluate_boolean(const xpath_node& n) const; 910 | 911 | // Evaluate expression as double value in the specified context; performs type conversion if necessary. 912 | // If PUGIXML_NO_EXCEPTIONS is not defined, throws std::bad_alloc on out of memory errors. 913 | double evaluate_number(const xpath_node& n) const; 914 | 915 | #ifndef PUGIXML_NO_STL 916 | // Evaluate expression as string value in the specified context; performs type conversion if necessary. 917 | // If PUGIXML_NO_EXCEPTIONS is not defined, throws std::bad_alloc on out of memory errors. 918 | string_t evaluate_string(const xpath_node& n) const; 919 | #endif 920 | 921 | // Evaluate expression as string value in the specified context; performs type conversion if necessary. 922 | // At most capacity characters are written to the destination buffer, full result size is returned (includes terminating zero). 923 | // If PUGIXML_NO_EXCEPTIONS is not defined, throws std::bad_alloc on out of memory errors. 924 | // If PUGIXML_NO_EXCEPTIONS is defined, returns empty set instead. 925 | size_t evaluate_string(char_t* buffer, size_t capacity, const xpath_node& n) const; 926 | 927 | // Evaluate expression as node set in the specified context. 928 | // If PUGIXML_NO_EXCEPTIONS is not defined, throws xpath_exception on type mismatch and std::bad_alloc on out of memory errors. 929 | // If PUGIXML_NO_EXCEPTIONS is defined, returns empty node set instead. 930 | xpath_node_set evaluate_node_set(const xpath_node& n) const; 931 | 932 | // Get parsing result (used to get compilation errors in PUGIXML_NO_EXCEPTIONS mode) 933 | const xpath_parse_result& result() const; 934 | 935 | // Safe bool conversion operator 936 | operator unspecified_bool_type() const; 937 | 938 | // Borland C++ workaround 939 | bool operator!() const; 940 | }; 941 | 942 | #ifndef PUGIXML_NO_EXCEPTIONS 943 | // XPath exception class 944 | class PUGIXML_CLASS xpath_exception: public std::exception 945 | { 946 | private: 947 | xpath_parse_result _result; 948 | 949 | public: 950 | // Construct exception from parse result 951 | explicit xpath_exception(const xpath_parse_result& result); 952 | 953 | // Get error message 954 | virtual const char* what() const throw(); 955 | 956 | // Get parse result 957 | const xpath_parse_result& result() const; 958 | }; 959 | #endif 960 | 961 | // XPath node class (either xml_node or xml_attribute) 962 | class PUGIXML_CLASS xpath_node 963 | { 964 | private: 965 | xml_node _node; 966 | xml_attribute _attribute; 967 | 968 | typedef xml_node xpath_node::*unspecified_bool_type; 969 | 970 | public: 971 | // Default constructor; constructs empty XPath node 972 | xpath_node(); 973 | 974 | // Construct XPath node from XML node/attribute 975 | xpath_node(const xml_node& node); 976 | xpath_node(const xml_attribute& attribute, const xml_node& parent); 977 | 978 | // Get node/attribute, if any 979 | xml_node node() const; 980 | xml_attribute attribute() const; 981 | 982 | // Get parent of contained node/attribute 983 | xml_node parent() const; 984 | 985 | // Safe bool conversion operator 986 | operator unspecified_bool_type() const; 987 | 988 | // Borland C++ workaround 989 | bool operator!() const; 990 | 991 | // Comparison operators 992 | bool operator==(const xpath_node& n) const; 993 | bool operator!=(const xpath_node& n) const; 994 | }; 995 | 996 | #ifdef __BORLANDC__ 997 | // Borland C++ workaround 998 | bool PUGIXML_FUNCTION operator&&(const xpath_node& lhs, bool rhs); 999 | bool PUGIXML_FUNCTION operator||(const xpath_node& lhs, bool rhs); 1000 | #endif 1001 | 1002 | // A fixed-size collection of XPath nodes 1003 | class PUGIXML_CLASS xpath_node_set 1004 | { 1005 | public: 1006 | // Collection type 1007 | enum type_t 1008 | { 1009 | type_unsorted, // Not ordered 1010 | type_sorted, // Sorted by document order (ascending) 1011 | type_sorted_reverse // Sorted by document order (descending) 1012 | }; 1013 | 1014 | // Constant iterator type 1015 | typedef const xpath_node* const_iterator; 1016 | 1017 | // Default constructor. Constructs empty set. 1018 | xpath_node_set(); 1019 | 1020 | // Constructs a set from iterator range; data is not checked for duplicates and is not sorted according to provided type, so be careful 1021 | xpath_node_set(const_iterator begin, const_iterator end, type_t type = type_unsorted); 1022 | 1023 | // Destructor 1024 | ~xpath_node_set(); 1025 | 1026 | // Copy constructor/assignment operator 1027 | xpath_node_set(const xpath_node_set& ns); 1028 | xpath_node_set& operator=(const xpath_node_set& ns); 1029 | 1030 | // Get collection type 1031 | type_t type() const; 1032 | 1033 | // Get collection size 1034 | size_t size() const; 1035 | 1036 | // Indexing operator 1037 | const xpath_node& operator[](size_t index) const; 1038 | 1039 | // Collection iterators 1040 | const_iterator begin() const; 1041 | const_iterator end() const; 1042 | 1043 | // Sort the collection in ascending/descending order by document order 1044 | void sort(bool reverse = false); 1045 | 1046 | // Get first node in the collection by document order 1047 | xpath_node first() const; 1048 | 1049 | // Check if collection is empty 1050 | bool empty() const; 1051 | 1052 | private: 1053 | type_t _type; 1054 | 1055 | xpath_node _storage; 1056 | 1057 | xpath_node* _begin; 1058 | xpath_node* _end; 1059 | 1060 | void _assign(const_iterator begin, const_iterator end); 1061 | }; 1062 | #endif 1063 | 1064 | #ifndef PUGIXML_NO_STL 1065 | // Convert wide string to UTF8 1066 | std::basic_string, std::allocator > PUGIXML_FUNCTION as_utf8(const wchar_t* str); 1067 | std::basic_string, std::allocator > PUGIXML_FUNCTION as_utf8(const std::basic_string, std::allocator >& str); 1068 | 1069 | // Convert UTF8 to wide string 1070 | std::basic_string, std::allocator > PUGIXML_FUNCTION as_wide(const char* str); 1071 | std::basic_string, std::allocator > PUGIXML_FUNCTION as_wide(const std::basic_string, std::allocator >& str); 1072 | #endif 1073 | 1074 | // Memory allocation function interface; returns pointer to allocated memory or NULL on failure 1075 | typedef void* (*allocation_function)(size_t size); 1076 | 1077 | // Memory deallocation function interface 1078 | typedef void (*deallocation_function)(void* ptr); 1079 | 1080 | // Override default memory management functions. All subsequent allocations/deallocations will be performed via supplied functions. 1081 | void PUGIXML_FUNCTION set_memory_management_functions(allocation_function allocate, deallocation_function deallocate); 1082 | 1083 | // Get current memory management functions 1084 | allocation_function PUGIXML_FUNCTION get_memory_allocation_function(); 1085 | deallocation_function PUGIXML_FUNCTION get_memory_deallocation_function(); 1086 | } 1087 | 1088 | #if !defined(PUGIXML_NO_STL) && (defined(_MSC_VER) || defined(__ICC)) 1089 | namespace std 1090 | { 1091 | // Workarounds for (non-standard) iterator category detection for older versions (MSVC7/IC8 and earlier) 1092 | std::bidirectional_iterator_tag PUGIXML_FUNCTION _Iter_cat(const pugi::xml_node_iterator&); 1093 | std::bidirectional_iterator_tag PUGIXML_FUNCTION _Iter_cat(const pugi::xml_attribute_iterator&); 1094 | } 1095 | #endif 1096 | 1097 | #if !defined(PUGIXML_NO_STL) && defined(__SUNPRO_CC) 1098 | namespace std 1099 | { 1100 | // Workarounds for (non-standard) iterator category detection 1101 | std::bidirectional_iterator_tag PUGIXML_FUNCTION __iterator_category(const pugi::xml_node_iterator&); 1102 | std::bidirectional_iterator_tag PUGIXML_FUNCTION __iterator_category(const pugi::xml_attribute_iterator&); 1103 | } 1104 | #endif 1105 | 1106 | #endif 1107 | 1108 | /** 1109 | * Copyright (c) 2006-2010 Arseny Kapoulkine 1110 | * 1111 | * Permission is hereby granted, free of charge, to any person 1112 | * obtaining a copy of this software and associated documentation 1113 | * files (the "Software"), to deal in the Software without 1114 | * restriction, including without limitation the rights to use, 1115 | * copy, modify, merge, publish, distribute, sublicense, and/or sell 1116 | * copies of the Software, and to permit persons to whom the 1117 | * Software is furnished to do so, subject to the following 1118 | * conditions: 1119 | * 1120 | * The above copyright notice and this permission notice shall be 1121 | * included in all copies or substantial portions of the Software. 1122 | * 1123 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, 1124 | * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES 1125 | * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND 1126 | * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT 1127 | * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, 1128 | * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING 1129 | * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR 1130 | * OTHER DEALINGS IN THE SOFTWARE. 1131 | */ 1132 | -------------------------------------------------------------------------------- /testApp.cpp: -------------------------------------------------------------------------------- 1 | #include "CRobot.h" 2 | #include "CConfigLoader.h" 3 | #include "CLineFactory.h" 4 | #include "CAlgoAbstract.h" 5 | #include "CJacobianTranspose.h" 6 | #include "CDumpedLeastSquares.h" 7 | #include "CAlgoFactory.h" 8 | #include 9 | 10 | #define _TESTDLS 11 | 12 | int main() 13 | { 14 | 15 | #ifdef _TEST1 16 | 17 | std::string str = "robot.xml"; 18 | CConfigLoader cfg(str); 19 | if(!cfg.LoadXml()) return 1; 20 | //Set origin at O_zero 21 | CRobot robot(Vector3f(0.0f,0.0f,0.0f)); 22 | robot.LoadConfig(cfg.GetTable()); 23 | //Print loaded data 24 | robot.PrintHomogenTransformationMatrix(); 25 | robot.PrintFullTransformationMatrix(); 26 | //Rotating joint 1 for 90 degrees 27 | robot.RotateJoint(DHINDEX(1),90.0f); 28 | robot.PrintHomogenTransformationMatrix(); 29 | robot.PrintFullTransformationMatrix(); 30 | 31 | #endif 32 | 33 | #ifdef _TEST2 34 | 35 | CLine3D line; 36 | Vector3f test2; 37 | Vector3f vec_end(20,1,0); 38 | Vector3f vec_start(1,2,3); 39 | float displ = 0.01f; 40 | 41 | test2 = line.GetNextPoint(vec_end,vec_start,displ); 42 | 43 | while(true) 44 | { 45 | if (test2 == vec_end) 46 | { 47 | break; 48 | } 49 | 50 | std::cout<SetAdditionalParametr(speccfc); 74 | pJpt->CalculateData(); 75 | robot.PrintConfiguration(); 76 | 77 | #endif 78 | 79 | #ifdef _TESTJACIBIANPSEUDO 80 | 81 | std::string str = "robot.xml"; 82 | CConfigLoader cfg(str); 83 | if(!cfg.LoadXml()) return 1; 84 | //Set origin at O_zero 85 | CRobot robot(Vector3f(0.0f,0.0f,0.0f)); 86 | robot.LoadConfig(cfg.GetTable()); 87 | CAlgoFactory factory; 88 | VectorXf des(6); 89 | float speccfc = 0.001f; 90 | des << 200.0f , 200.0f , 0.0f , 0.0f , 0.0f , 0.0f ; 91 | 92 | CAlgoAbstract * pJpt = factory.GiveMeSolver(JACOBIANPSEVDOINVERSE,des,robot); 93 | pJpt->CalculateData(); 94 | robot.PrintConfiguration(); 95 | 96 | #endif 97 | 98 | #ifdef _TESTDLS 99 | 100 | std::string str = "robot.xml"; 101 | CConfigLoader cfg(str); 102 | if(!cfg.LoadXml()) return 1; 103 | //Set origin at O_zero 104 | CRobot robot(Vector3f(0.0f,0.0f,0.0f)); 105 | robot.LoadConfig(cfg.GetTable()); 106 | CAlgoFactory factory; 107 | VectorXf des(6); 108 | float speccfc = 0.001f; 109 | des << 200.0f , 200.0f , 0.0f , 0.0f , 0.0f , 0.0f ; 110 | 111 | CAlgoAbstract * pJpt = factory.GiveMeSolver(DUMPEDLEASTSQUARES,des,robot); 112 | pJpt->SetAdditionalParametr(speccfc); 113 | pJpt->CalculateData(); 114 | robot.PrintConfiguration(); 115 | 116 | #endif 117 | 118 | return 0; 119 | } --------------------------------------------------------------------------------