diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..af96791 --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +.vscode +build diff --git a/CMakeLists.txt b/CMakeLists.txt index 65723b4..6811c18 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,4 +64,4 @@ link_directories(lib) # ----------------------add executable---------------------- set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}) add_executable(z1_ctrl main.cpp) -target_link_libraries(z1_ctrl libZ1_${COMMUNICATION}_Linux64.so ${catkin_LIBRARIES} ) +target_link_libraries(z1_ctrl libZ1_${COMMUNICATION}_${CMAKE_HOST_SYSTEM_PROCESSOR}.so ${catkin_LIBRARIES} ) diff --git a/include/FSM/BaseState.h b/include/FSM/BaseState.h index 43d9071..96b7249 100755 --- a/include/FSM/BaseState.h +++ b/include/FSM/BaseState.h @@ -1,32 +1,32 @@ -#ifndef BASESTATE_H -#define BASESTATE_H - -#include -#include "common/enumClass.h" - -class BaseState{ -public: - BaseState(int stateNameEnum, std::string stateNameString) - : _stateNameEnum(stateNameEnum), _stateNameString(stateNameString){} - virtual ~BaseState(){}; - - virtual void enter() = 0; - virtual void run() = 0; - virtual void exit() = 0; - virtual int checkChange(int cmd) = 0; - - bool isState(int stateEnum){ - if(_stateNameEnum == stateEnum){ - return true; - }else{ - return false; - } - } - std::string getStateName(){return _stateNameString;} - int getStateNameEnum(){return _stateNameEnum;}; -protected: - int _stateNameEnum; - std::string _stateNameString; -}; - +#ifndef BASESTATE_H +#define BASESTATE_H + +#include +#include "common/enumClass.h" + +class BaseState{ +public: + BaseState(int stateNameEnum, std::string stateNameString) + : _stateNameEnum(stateNameEnum), _stateNameString(stateNameString){} + virtual ~BaseState(){}; + + virtual void enter() = 0; + virtual void run() = 0; + virtual void exit() = 0; + virtual int checkChange(int cmd) = 0; + + bool isState(int stateEnum){ + if(_stateNameEnum == stateEnum){ + return true; + }else{ + return false; + } + } + std::string getStateName(){return _stateNameString;} + int getStateNameEnum(){return _stateNameEnum;}; +protected: + int _stateNameEnum; + std::string _stateNameString; +}; + #endif \ No newline at end of file diff --git a/include/FSM/FSMState.h b/include/FSM/FSMState.h index 3fafdeb..7e45a39 100755 --- a/include/FSM/FSMState.h +++ b/include/FSM/FSMState.h @@ -1,49 +1,49 @@ -#ifndef FSMSTATE_H -#define FSMSTATE_H - -#include -#include -#include -#include "control/CtrlComponents.h" -#include "common/math/mathTools.h" -#include "common/utilities/timer.h" -#include "FSM/BaseState.h" - -class FSMState : public BaseState{ -public: - FSMState(CtrlComponents *ctrlComp, ArmFSMStateName stateName, std::string stateNameString); - virtual ~FSMState(){} - - virtual void enter() = 0; - virtual void run() = 0; - virtual void exit() = 0; - virtual int checkChange(int cmd) {return (int)ArmFSMStateName::INVALID;} - bool _collisionTest(); - -protected: - void _armCtrl(); - void _recordData(); - Vec6 _postureToVec6(Posture posture); - void _tauFriction(); - - LowlevelCmd *_lowCmd; - LowlevelState *_lowState; - IOInterface *_ioInter; - ArmModel *_armModel; - - Vec6 _qPast, _qdPast, _q, _qd, _qdd, _tauForward; - double _gripperPos, _gripperW, _gripperTau; - - CtrlComponents *_ctrlComp; - Vec6 _g, _tauCmd, _tauFric; - -private: - - uint _collisionCnt; - - Vec6 _mLinearFriction; - Vec6 _mCoulombFriction; - -}; - -#endif // FSMSTATE_H +#ifndef FSMSTATE_H +#define FSMSTATE_H + +#include +#include +#include +#include "control/CtrlComponents.h" +#include "common/math/mathTools.h" +#include "common/utilities/timer.h" +#include "FSM/BaseState.h" + +class FSMState : public BaseState{ +public: + FSMState(CtrlComponents *ctrlComp, ArmFSMStateName stateName, std::string stateNameString); + virtual ~FSMState(){} + + virtual void enter() = 0; + virtual void run() = 0; + virtual void exit() = 0; + virtual int checkChange(int cmd) {return (int)ArmFSMStateName::INVALID;} + bool _collisionTest(); + +protected: + void _armCtrl(); + void _recordData(); + Vec6 _postureToVec6(Posture posture); + void _tauFriction(); + + LowlevelCmd *_lowCmd; + LowlevelState *_lowState; + IOInterface *_ioInter; + ArmModel *_armModel; + + Vec6 _qPast, _qdPast, _q, _qd, _qdd, _tauForward; + double _gripperPos, _gripperW, _gripperTau; + + CtrlComponents *_ctrlComp; + Vec6 _g, _tauCmd, _tauFric; + +private: + + uint _collisionCnt; + + Vec6 _mLinearFriction; + Vec6 _mCoulombFriction; + +}; + +#endif // FSMSTATE_H diff --git a/include/FSM/FiniteStateMachine.h b/include/FSM/FiniteStateMachine.h index e6d1df7..4fcb3e6 100755 --- a/include/FSM/FiniteStateMachine.h +++ b/include/FSM/FiniteStateMachine.h @@ -1,28 +1,28 @@ -#ifndef FSM_H -#define FSM_H - -#include -#include "FSM/FSMState.h" -#include "common/utilities/loop.h" -#include "control/CtrlComponents.h" - -class FiniteStateMachine{ -public: - FiniteStateMachine(std::vector states, CtrlComponents *ctrlComp); - virtual ~FiniteStateMachine(); - -private: - void _run(); - std::vector _states; - - FSMMode _mode; - bool _running; - FSMState* _currentState; - FSMState* _nextState; - int _nextStateEnum; - - CtrlComponents *_ctrlComp; - LoopFunc *_runThread; -}; - +#ifndef FSM_H +#define FSM_H + +#include +#include "FSM/FSMState.h" +#include "common/utilities/loop.h" +#include "control/CtrlComponents.h" + +class FiniteStateMachine{ +public: + FiniteStateMachine(std::vector states, CtrlComponents *ctrlComp); + virtual ~FiniteStateMachine(); + +private: + void _run(); + std::vector _states; + + FSMMode _mode; + bool _running; + FSMState* _currentState; + FSMState* _nextState; + int _nextStateEnum; + + CtrlComponents *_ctrlComp; + LoopFunc *_runThread; +}; + #endif // FSM_H \ No newline at end of file diff --git a/include/FSM/State_BackToStart.h b/include/FSM/State_BackToStart.h index 61f239f..6c811ba 100644 --- a/include/FSM/State_BackToStart.h +++ b/include/FSM/State_BackToStart.h @@ -1,22 +1,22 @@ -#ifndef STATE_BACKTOSTART_H -#define STATE_BACKTOSTART_H - - -#include "FSM/FSMState.h" -#include "trajectory/JointSpaceTraj.h" - -class State_BackToStart : public FSMState{ -public: - State_BackToStart(CtrlComponents *ctrlComp); - ~State_BackToStart(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - bool _reach, _pastReach; - JointSpaceTraj *_jointTraj; - Vec6 _pos_startFlat; -}; - +#ifndef STATE_BACKTOSTART_H +#define STATE_BACKTOSTART_H + + +#include "FSM/FSMState.h" +#include "trajectory/JointSpaceTraj.h" + +class State_BackToStart : public FSMState{ +public: + State_BackToStart(CtrlComponents *ctrlComp); + ~State_BackToStart(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + bool _reach, _pastReach; + JointSpaceTraj *_jointTraj; + Vec6 _pos_startFlat; +}; + #endif // STATE_BACKTOSTART_H \ No newline at end of file diff --git a/include/FSM/State_Calibration.h b/include/FSM/State_Calibration.h index 4668eb9..87d7404 100644 --- a/include/FSM/State_Calibration.h +++ b/include/FSM/State_Calibration.h @@ -1,18 +1,18 @@ -#ifndef STATE_CALIBRATION_H -#define STATE_CALIBRATION_H - -#include "FSM/FSMState.h" - -class State_Calibration : public FSMState{ -public: - State_Calibration(CtrlComponents *ctrlComp); - ~State_Calibration(){} - void enter(); - void run(){}; - void exit(){}; - int checkChange(int cmd); -private: - -}; - +#ifndef STATE_CALIBRATION_H +#define STATE_CALIBRATION_H + +#include "FSM/FSMState.h" + +class State_Calibration : public FSMState{ +public: + State_Calibration(CtrlComponents *ctrlComp); + ~State_Calibration(){} + void enter(); + void run(){}; + void exit(){}; + int checkChange(int cmd); +private: + +}; + #endif // STATE_CALIBRATION_H \ No newline at end of file diff --git a/include/FSM/State_Cartesian.h b/include/FSM/State_Cartesian.h old mode 100755 new mode 100644 diff --git a/include/FSM/State_JointSpace.h b/include/FSM/State_JointSpace.h index 4b7bbdd..5a421d5 100755 --- a/include/FSM/State_JointSpace.h +++ b/include/FSM/State_JointSpace.h @@ -1,18 +1,18 @@ -#ifndef JOINTSPACE_H -#define JOINTSPACE_H - -#include "FSM/FSMState.h" - -class State_JointSpace : public FSMState{ -public: - State_JointSpace(CtrlComponents *ctrlComp); - ~State_JointSpace(){} - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - std::vector jointSpeedMax; -}; - +#ifndef JOINTSPACE_H +#define JOINTSPACE_H + +#include "FSM/FSMState.h" + +class State_JointSpace : public FSMState{ +public: + State_JointSpace(CtrlComponents *ctrlComp); + ~State_JointSpace(){} + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + std::vector jointSpeedMax; +}; + #endif // JOINTSPACE_H \ No newline at end of file diff --git a/include/FSM/State_LowCmd.h b/include/FSM/State_LowCmd.h index ce00143..c528e87 100755 --- a/include/FSM/State_LowCmd.h +++ b/include/FSM/State_LowCmd.h @@ -1,18 +1,18 @@ -#ifndef LOWCMD_H -#define LOWCMD_H - -#include "FSMState.h" - -class State_LowCmd : public FSMState{ -public: - State_LowCmd(CtrlComponents *ctrlComp); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - std::vector _kp; - std::vector _kw; -}; - +#ifndef LOWCMD_H +#define LOWCMD_H + +#include "FSMState.h" + +class State_LowCmd : public FSMState{ +public: + State_LowCmd(CtrlComponents *ctrlComp); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + std::vector _kp; + std::vector _kw; +}; + #endif // LOWCMD_H \ No newline at end of file diff --git a/include/FSM/State_MoveC.h b/include/FSM/State_MoveC.h index a226e61..9843ee0 100755 --- a/include/FSM/State_MoveC.h +++ b/include/FSM/State_MoveC.h @@ -1,23 +1,23 @@ -#ifndef MOVEC_H -#define MOVEC_H - -#include "FSM/FSMState.h" -#include "trajectory/EndCircleTraj.h" - -class State_MoveC : public FSMState{ -public: - State_MoveC(CtrlComponents *ctrlComp); - ~State_MoveC(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - double _speed; - std::vector _postures; - EndCircleTraj *_circleTraj; - bool _timeReached, _taskReached, _pastTaskReached, _finalReached; - uint _taskCnt; -}; - +#ifndef MOVEC_H +#define MOVEC_H + +#include "FSM/FSMState.h" +#include "trajectory/EndCircleTraj.h" + +class State_MoveC : public FSMState{ +public: + State_MoveC(CtrlComponents *ctrlComp); + ~State_MoveC(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + double _speed; + std::vector _postures; + EndCircleTraj *_circleTraj; + bool _timeReached, _taskReached, _pastTaskReached, _finalReached; + uint _taskCnt; +}; + #endif // CARTESIAN_H \ No newline at end of file diff --git a/include/FSM/State_MoveJ.h b/include/FSM/State_MoveJ.h old mode 100755 new mode 100644 diff --git a/include/FSM/State_MoveL.h b/include/FSM/State_MoveL.h old mode 100755 new mode 100644 diff --git a/include/FSM/State_Passive.h b/include/FSM/State_Passive.h index b4c4306..b3702d2 100755 --- a/include/FSM/State_Passive.h +++ b/include/FSM/State_Passive.h @@ -1,15 +1,15 @@ -#ifndef PASSIVE_H -#define PASSIVE_H - -#include "FSM/FSMState.h" - -class State_Passive : public FSMState{ -public: - State_Passive(CtrlComponents *ctrlComp); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -}; - +#ifndef PASSIVE_H +#define PASSIVE_H + +#include "FSM/FSMState.h" + +class State_Passive : public FSMState{ +public: + State_Passive(CtrlComponents *ctrlComp); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +}; + #endif // PASSIVE_H \ No newline at end of file diff --git a/include/FSM/State_SaveState.h b/include/FSM/State_SaveState.h index 5393fc7..412bc71 100755 --- a/include/FSM/State_SaveState.h +++ b/include/FSM/State_SaveState.h @@ -1,18 +1,18 @@ -#ifndef SAVESTATE_H -#define SAVESTATE_H - -#include "FSMState.h" -#include "common/utilities/CSVTool.h" - -class State_SaveState : public FSMState{ -public: - State_SaveState(CtrlComponents *ctrlComp); - ~State_SaveState(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: -}; - +#ifndef SAVESTATE_H +#define SAVESTATE_H + +#include "FSMState.h" +#include "common/utilities/CSVTool.h" + +class State_SaveState : public FSMState{ +public: + State_SaveState(CtrlComponents *ctrlComp); + ~State_SaveState(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: +}; + #endif // SAVESTATE_H \ No newline at end of file diff --git a/include/FSM/State_Teach.h b/include/FSM/State_Teach.h index 0bfcbb9..d4cb058 100755 --- a/include/FSM/State_Teach.h +++ b/include/FSM/State_Teach.h @@ -1,24 +1,24 @@ -#ifndef STATETEACH_H -#define STATETEACH_H - -#include "FSM/FSMState.h" - -class State_Teach : public FSMState{ -public: - State_Teach(CtrlComponents *ctrlComp); - ~State_Teach(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - CSVTool *_trajCSV; - size_t _stateID = 0; - - Vec6 _KdDiag; - Vec6 _kpForStable; - Mat6 _Kd; - double _errorBias; -}; - +#ifndef STATETEACH_H +#define STATETEACH_H + +#include "FSM/FSMState.h" + +class State_Teach : public FSMState{ +public: + State_Teach(CtrlComponents *ctrlComp); + ~State_Teach(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + CSVTool *_trajCSV; + size_t _stateID = 0; + + Vec6 _KdDiag; + Vec6 _kpForStable; + Mat6 _Kd; + double _errorBias; +}; + #endif // STATETEACH_H \ No newline at end of file diff --git a/include/FSM/State_TeachRepeat.h b/include/FSM/State_TeachRepeat.h index e79802e..9d816bf 100755 --- a/include/FSM/State_TeachRepeat.h +++ b/include/FSM/State_TeachRepeat.h @@ -1,28 +1,28 @@ -#ifndef STATE_TEACHREPEAT_H -#define STATE_TEACHREPEAT_H - -#include "FSM/FSMState.h" -#include "trajectory/TrajectoryManager.h" - -class State_TeachRepeat : public FSMState{ -public: - State_TeachRepeat(CtrlComponents *ctrlComp); - ~State_TeachRepeat(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - bool _setCorrectly; - JointSpaceTraj *_toStartTraj; - bool _reachedStart = false; - bool _finishedRepeat = false; - size_t _index = 0; - size_t _indexPast; - Vec6 _trajStartQ, _trajStartQd; - double _trajStartGripperQ, _trajStartGripperQd; - - CSVTool *_csvFile; -}; - +#ifndef STATE_TEACHREPEAT_H +#define STATE_TEACHREPEAT_H + +#include "FSM/FSMState.h" +#include "trajectory/TrajectoryManager.h" + +class State_TeachRepeat : public FSMState{ +public: + State_TeachRepeat(CtrlComponents *ctrlComp); + ~State_TeachRepeat(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + bool _setCorrectly; + JointSpaceTraj *_toStartTraj; + bool _reachedStart = false; + bool _finishedRepeat = false; + size_t _index = 0; + size_t _indexPast; + Vec6 _trajStartQ, _trajStartQd; + double _trajStartGripperQ, _trajStartGripperQd; + + CSVTool *_csvFile; +}; + #endif // STATE_TEACHREPEAT_H \ No newline at end of file diff --git a/include/FSM/State_ToState.h b/include/FSM/State_ToState.h index 066ceb3..e063f77 100755 --- a/include/FSM/State_ToState.h +++ b/include/FSM/State_ToState.h @@ -1,24 +1,24 @@ -#ifndef TOSTATE_H -#define TOSTATE_H - -#include "FSM/FSMState.h" -#include "trajectory/JointSpaceTraj.h" - -class State_ToState : public FSMState{ -public: - State_ToState(CtrlComponents *ctrlComp); - ~State_ToState(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -private: - bool _setCorrectly; - double _costTime; - HomoMat _goalHomo; - JointSpaceTraj *_jointTraj; - bool _reach, _pastReach; - std::string _goalName; -}; - +#ifndef TOSTATE_H +#define TOSTATE_H + +#include "FSM/FSMState.h" +#include "trajectory/JointSpaceTraj.h" + +class State_ToState : public FSMState{ +public: + State_ToState(CtrlComponents *ctrlComp); + ~State_ToState(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +private: + bool _setCorrectly; + double _costTime; + HomoMat _goalHomo; + JointSpaceTraj *_jointTraj; + bool _reach, _pastReach; + std::string _goalName; +}; + #endif // TOSTATE_H \ No newline at end of file diff --git a/include/FSM/State_Trajectory.h b/include/FSM/State_Trajectory.h index 9955df9..a5da191 100755 --- a/include/FSM/State_Trajectory.h +++ b/include/FSM/State_Trajectory.h @@ -1,37 +1,37 @@ -#ifndef CARTESIANPATH_H -#define CARTESIANPATH_H - -#include "FSM/FSMState.h" -#include "trajectory/TrajectoryManager.h" - -class State_Trajectory : public FSMState{ -public: - State_Trajectory(CtrlComponents *ctrlComp, - ArmFSMStateName stateEnum = ArmFSMStateName::TRAJECTORY, - std::string stateString = "trajectory"); - ~State_Trajectory(); - void enter(); - void run(); - void exit(); - int checkChange(int cmd); -protected: - void _setTraj(); - - TrajectoryManager *_traj; - HomoMat _goalHomo; - Vec6 _goalTwist; - double speedTemp; - - JointSpaceTraj *_toStartTraj; - bool _reachedStart = false; - bool _finishedTraj = false; - std::vector _jointTraj; - std::vector _circleTraj; - std::vector _stopTraj; - std::vector _lineTraj; - - static std::vector _trajCmd; - Vec6 _posture[2]; -}; - +#ifndef CARTESIANPATH_H +#define CARTESIANPATH_H + +#include "FSM/FSMState.h" +#include "trajectory/TrajectoryManager.h" + +class State_Trajectory : public FSMState{ +public: + State_Trajectory(CtrlComponents *ctrlComp, + ArmFSMStateName stateEnum = ArmFSMStateName::TRAJECTORY, + std::string stateString = "trajectory"); + ~State_Trajectory(); + void enter(); + void run(); + void exit(); + int checkChange(int cmd); +protected: + void _setTraj(); + + TrajectoryManager *_traj; + HomoMat _goalHomo; + Vec6 _goalTwist; + double speedTemp; + + JointSpaceTraj *_toStartTraj; + bool _reachedStart = false; + bool _finishedTraj = false; + std::vector _jointTraj; + std::vector _circleTraj; + std::vector _stopTraj; + std::vector _lineTraj; + + static std::vector _trajCmd; + Vec6 _posture[2]; +}; + #endif // CARTESIANPATH_H \ No newline at end of file diff --git a/include/common/enumClass.h b/include/common/enumClass.h index a48e186..754a835 100755 --- a/include/common/enumClass.h +++ b/include/common/enumClass.h @@ -1,39 +1,39 @@ -#ifndef ENUMCLASS_H -#define ENUMCLASS_H - -enum class FSMMode{ - NORMAL, - CHANGE -}; - -enum class ArmFSMStateName{ - INVALID, - PASSIVE, - JOINTCTRL, - CARTESIAN, - MOVEJ, - MOVEL, - MOVEC, - TRAJECTORY, - TOSTATE, - SAVESTATE, - TEACH, - TEACHREPEAT, - CALIBRATION, - SETTRAJ,//no longer used - BACKTOSTART, - NEXT, - LOWCMD -}; - -enum class JointMotorType{ - SINGLE_MOTOR, - DOUBLE_MOTOR -}; - -enum class Control{ - KEYBOARD, - SDK -}; - +#ifndef ENUMCLASS_H +#define ENUMCLASS_H + +enum class FSMMode{ + NORMAL, + CHANGE +}; + +enum class ArmFSMStateName{ + INVALID, + PASSIVE, + JOINTCTRL, + CARTESIAN, + MOVEJ, + MOVEL, + MOVEC, + TRAJECTORY, + TOSTATE, + SAVESTATE, + TEACH, + TEACHREPEAT, + CALIBRATION, + SETTRAJ,//no longer used + BACKTOSTART, + NEXT, + LOWCMD +}; + +enum class JointMotorType{ + SINGLE_MOTOR, + DOUBLE_MOTOR +}; + +enum class Control{ + KEYBOARD, + SDK +}; + #endif // ENUMCLASS_H \ No newline at end of file diff --git a/include/common/math/Filter.h b/include/common/math/Filter.h old mode 100644 new mode 100755 index ec421da..c5bebe3 --- a/include/common/math/Filter.h +++ b/include/common/math/Filter.h @@ -1,29 +1,29 @@ -#ifndef FILTER -#define FILTER - -#include -#include - -/* - Low pass filter -*/ -class LPFilter{ -public: - LPFilter(double samplePeriod, double cutFrequency, size_t valueCount); - ~LPFilter(){}; - void clear(); - void addValue(double &newValue); - void addValue(std::vector &vec); - - template - void addValue(Eigen::MatrixBase &eigenVec); - - // double getValue(); -private: - size_t _valueCount; - double _weight; - std::vector _pastValue; - bool _start; -}; - +#ifndef FILTER +#define FILTER + +#include +#include + +/* + Low pass filter +*/ +class LPFilter{ +public: + LPFilter(double samplePeriod, double cutFrequency, size_t valueCount); + ~LPFilter(){}; + void clear(); + void addValue(double &newValue); + void addValue(std::vector &vec); + + template + void addValue(Eigen::MatrixBase &eigenVec); + + // double getValue(); +private: + size_t _valueCount; + double _weight; + std::vector _pastValue; + bool _start; +}; + #endif // FILTER \ No newline at end of file diff --git a/include/common/math/mathTypes.h b/include/common/math/mathTypes.h index b74c7d7..08ca8a6 100755 --- a/include/common/math/mathTypes.h +++ b/include/common/math/mathTypes.h @@ -1,109 +1,109 @@ -#ifndef MATHTYPES_H -#define MATHTYPES_H - -#include -#include - -/************************/ -/******** Vector ********/ -/************************/ -// 2x1 Vector -using Vec2 = typename Eigen::Matrix; - -// 3x1 Vector -using Vec3 = typename Eigen::Matrix; - -// 4x1 Vector -using Vec4 = typename Eigen::Matrix; - -// 6x1 Vector -using Vec6 = typename Eigen::Matrix; - -// Quaternion -using Quat = typename Eigen::Matrix; - -// 4x1 Integer Vector -using VecInt4 = typename Eigen::Matrix; - -// 12x1 Vector -using Vec12 = typename Eigen::Matrix; - -// 18x1 Vector -using Vec18 = typename Eigen::Matrix; - -// Dynamic Length Vector -using VecX = typename Eigen::Matrix; - -/************************/ -/******** Matrix ********/ -/************************/ -// Rotation Matrix -using RotMat = typename Eigen::Matrix; - -// Homogenous Matrix -using HomoMat = typename Eigen::Matrix; - -// 2x2 Matrix -using Mat2 = typename Eigen::Matrix; - -// 3x3 Matrix -using Mat3 = typename Eigen::Matrix; - -// 3x4 Matrix, each column is a 3x1 vector -using Vec34 = typename Eigen::Matrix; - -// 6x6 Matrix -using Mat6 = typename Eigen::Matrix; - -// 12x12 Matrix -using Mat12 = typename Eigen::Matrix; - -// 3x3 Identity Matrix -#define I3 Eigen::MatrixXd::Identity(3, 3) - -// 6x6 Identity Matrix -#define I6 Eigen::MatrixXd::Identity(6, 6) - -// 12x12 Identity Matrix -#define I12 Eigen::MatrixXd::Identity(12, 12) - -// 18x18 Identity Matrix -#define I18 Eigen::MatrixXd::Identity(18, 18) - -// Dynamic Size Matrix -using MatX = typename Eigen::Matrix; - -/************************/ -/****** Functions *******/ -/************************/ -inline Vec34 vec12ToVec34(Vec12 vec12){ - Vec34 vec34; - for(int i(0); i < 4; ++i){ - vec34.col(i) = vec12.segment(3*i, 3); - } - return vec34; -} - -inline Vec12 vec34ToVec12(Vec34 vec34){ - Vec12 vec12; - for(int i(0); i < 4; ++i){ - vec12.segment(3*i, 3) = vec34.col(i); - } - return vec12; -} - -template -inline VecX stdVecToEigenVec(T stdVec){ - VecX eigenVec = Eigen::VectorXd::Map(&stdVec[0], stdVec.size()); - return eigenVec; -} - -inline std::vector EigenVectostdVec(VecX eigenVec){ - std::vector stdVec; - for(int i(0); i +#include + +/************************/ +/******** Vector ********/ +/************************/ +// 2x1 Vector +using Vec2 = typename Eigen::Matrix; + +// 3x1 Vector +using Vec3 = typename Eigen::Matrix; + +// 4x1 Vector +using Vec4 = typename Eigen::Matrix; + +// 6x1 Vector +using Vec6 = typename Eigen::Matrix; + +// Quaternion +using Quat = typename Eigen::Matrix; + +// 4x1 Integer Vector +using VecInt4 = typename Eigen::Matrix; + +// 12x1 Vector +using Vec12 = typename Eigen::Matrix; + +// 18x1 Vector +using Vec18 = typename Eigen::Matrix; + +// Dynamic Length Vector +using VecX = typename Eigen::Matrix; + +/************************/ +/******** Matrix ********/ +/************************/ +// Rotation Matrix +using RotMat = typename Eigen::Matrix; + +// Homogenous Matrix +using HomoMat = typename Eigen::Matrix; + +// 2x2 Matrix +using Mat2 = typename Eigen::Matrix; + +// 3x3 Matrix +using Mat3 = typename Eigen::Matrix; + +// 3x4 Matrix, each column is a 3x1 vector +using Vec34 = typename Eigen::Matrix; + +// 6x6 Matrix +using Mat6 = typename Eigen::Matrix; + +// 12x12 Matrix +using Mat12 = typename Eigen::Matrix; + +// 3x3 Identity Matrix +#define I3 Eigen::MatrixXd::Identity(3, 3) + +// 6x6 Identity Matrix +#define I6 Eigen::MatrixXd::Identity(6, 6) + +// 12x12 Identity Matrix +#define I12 Eigen::MatrixXd::Identity(12, 12) + +// 18x18 Identity Matrix +#define I18 Eigen::MatrixXd::Identity(18, 18) + +// Dynamic Size Matrix +using MatX = typename Eigen::Matrix; + +/************************/ +/****** Functions *******/ +/************************/ +inline Vec34 vec12ToVec34(Vec12 vec12){ + Vec34 vec34; + for(int i(0); i < 4; ++i){ + vec34.col(i) = vec12.segment(3*i, 3); + } + return vec34; +} + +inline Vec12 vec34ToVec12(Vec34 vec34){ + Vec12 vec12; + for(int i(0); i < 4; ++i){ + vec12.segment(3*i, 3) = vec34.col(i); + } + return vec12; +} + +template +inline VecX stdVecToEigenVec(T stdVec){ + VecX eigenVec = Eigen::VectorXd::Map(&stdVec[0], stdVec.size()); + return eigenVec; +} + +inline std::vector EigenVectostdVec(VecX eigenVec){ + std::vector stdVec; + for(int i(0); i (read only) - */ -#include -#include -#include -#include -#include -#include -#include -#include -#include "common/utilities/typeTrans.h" - -enum class FileType{ - READ_WRITE, - CLEAR_DUMP -}; - -class CSVLine{ -public: - // CSVLine(std::string lineTemp, std::streampos filePos); - CSVLine(std::string lineTemp); - CSVLine(std::string label, std::vector values); - ~CSVLine(){} - - // void updateFilePos(std::streampos filePos){_filePos = filePos;} - void getValues(std::vector &values); - void changeValue(std::vector values); - void writeAtEnd(std::fstream &ioStream); - std::string getLabel(){return _label;} - -private: - // std::streampos _filePos; - std::string _label; - std::vector _values; -}; - -/* -FileType::READ_WRITE : must already exist such fileName -FileType::CLEAR_DUMP : if do not exist such file, will create one -*/ -class CSVTool{ -public: - CSVTool(std::string fileName, FileType type = FileType::READ_WRITE, int precision = 6); - ~CSVTool(){_ioStream.close();} - - bool getLine(std::string label, std::vector &values); - template - bool getLineDirect(std::string label, Args&... values); - - void modifyLine(std::string label, std::vector &values, bool addNew); - template - void modifyLineDirect(std::string label, bool addNew, Args&... values); - - void readFile(); - void saveFile(); - - bool _hasFile; -private: - std::string _fileName; - std::fstream _ioStream; - int _precision; - std::string _lineTemp; - std::map _labels; - std::vector _lines; - -}; - -/*************************/ -/* CSVLine */ -/*************************/ -// CSVLine::CSVLine(std::string lineTemp, std::streampos filePos) -// :_filePos(filePos){ - -// // std::cout << lineTemp << std::endl; -// } - -inline CSVLine::CSVLine(std::string lineTemp){ - // delete all spaces - lineTemp.erase(std::remove(lineTemp.begin(), lineTemp.end(), ' '), lineTemp.end()); - - std::stringstream ss(lineTemp); - std::string stringTemp; - - std::getline(ss, _label, ','); - - while(std::getline(ss, stringTemp, ',')){ - _values.push_back(stod(stringTemp)); - } - - // std::cout << "**********" << std::endl; - // std::cout << "_label: " << _label << std::fixed << std::setprecision(3) << std::endl; - // for(int i(0); i<_values.size(); ++i){ - // std::cout << _values.at(i) << ",,, "; - // } - // std::cout << std::endl; -} - -inline CSVLine::CSVLine(std::string label, std::vector values) - :_label(label), _values(values){ - -} - -inline void CSVLine::changeValue(std::vector values){ - if(values.size() != _values.size()){ - std::cout << "[WARNING] CSVLine::changeValue, the size changed" << std::endl; - } - _values = values; -} - -inline void CSVLine::getValues(std::vector &values){ - values = _values; -} - -inline void CSVLine::writeAtEnd(std::fstream &ioStream){ - ioStream << _label << ", "; - - for(int i(0); i<_values.size(); ++i){ - ioStream << _values.at(i) << ", "; - } - - ioStream << std::endl; -} - - -/*************************/ -/* CSVTool */ -/*************************/ -inline CSVTool::CSVTool(std::string fileName, FileType type, int precision) - : _fileName(fileName), _precision(precision){ - - if(type == FileType::READ_WRITE){ - _ioStream.open(_fileName, std::fstream::ate | std::fstream::in | std::fstream::out); - - if(!_ioStream.is_open()){ - std::cout << "[ERROR] CSVTool open file: " << fileName << " failed!" << std::endl; - // exit(-1); - _hasFile = false; - }else{ - readFile(); - _hasFile = true; - } - - } - else if(type == FileType::CLEAR_DUMP){ - _ioStream.open(_fileName, std::fstream::out); - } - -} - -inline void CSVTool::readFile(){ - if(!_ioStream.is_open()){ - // _ioStream.open(_fileName, std::fstream::ate | std::fstream::in | std::fstream::out); - std::cout << "[ERROR] CSVTool::readFile, file: " << _fileName << " has not been opened!" << std::endl; - return; - } - - _lines.clear(); - _labels.clear(); - - _ioStream.seekg(0, std::fstream::beg); - size_t lineNum = 0; - while(_ioStream && _ioStream.tellg() != std::fstream::end && getline(_ioStream, _lineTemp)){ - _lines.push_back( new CSVLine(_lineTemp) ); - - if(_labels.count(_lines.at(lineNum)->getLabel()) == 0){ - _labels.insert(std::pair(_lines.at(lineNum)->getLabel(), lineNum)); - ++lineNum; - }else{ - std::cout << "[ERROR] CSVTool::readFile, the label " - << _lines.at(lineNum)->getLabel() << " is repeated" << std::endl; - exit(-1); - } - } -} - -inline bool CSVTool::getLine(std::string label, std::vector &values){ - if(_labels.count(label) == 0){ - std::cout << "[ERROR] No such label: " << label << std::endl; - return false; - }else{ - _lines.at(_labels[label])->getValues(values); - return true; - } -} - -template -inline bool CSVTool::getLineDirect(std::string label, Args&... values){ - std::vector vec; - if(getLine(label, vec)){ - typeTrans::extractVector(vec, values...); - return true; - }else{ - return false; - } -} - -template -inline void CSVTool::modifyLineDirect(std::string label, bool addNew, Args&... values){ - std::vector vec; - typeTrans::combineToVector(vec, values...); - -// std::cout << "CSVTool::modifyLineDirect------" << std::endl; -// std::cout << "label: " << label << std::endl; -// std::cout << "vec: "; -// for(int i(0); iwriteAtEnd(_ioStream); - } - - _ioStream.close(); - _ioStream.open(_fileName, std::fstream::ate | std::fstream::in | std::fstream::out); -} - -inline void CSVTool::modifyLine(std::string label, std::vector &values, bool addNew =false){ - if(_labels.count(label) == 0){ - if(addNew){ - _labels.insert(std::pair(label, _labels.size())); - _lines.push_back(new CSVLine(label, values)); - }else{ - std::cout << "[ERROR] CSVTool::modifyLine, label " << label << "does not exist" << std::endl; - exit(-1); - } - }else{ - _lines.at(_labels[label])->changeValue(values); - } -} - - +#ifndef CSVTOOL_H +#define CSVTOOL_H + +/* + personal tool for .csv reading and modifying. + only suitable for small .csv file. + for large .csv, try (read only) + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include "common/utilities/typeTrans.h" + +enum class FileType{ + READ_WRITE, + CLEAR_DUMP +}; + +class CSVLine{ +public: + // CSVLine(std::string lineTemp, std::streampos filePos); + CSVLine(std::string lineTemp); + CSVLine(std::string label, std::vector values); + ~CSVLine(){} + + // void updateFilePos(std::streampos filePos){_filePos = filePos;} + void getValues(std::vector &values); + void changeValue(std::vector values); + void writeAtEnd(std::fstream &ioStream); + std::string getLabel(){return _label;} + +private: + // std::streampos _filePos; + std::string _label; + std::vector _values; +}; + +/* +FileType::READ_WRITE : must already exist such fileName +FileType::CLEAR_DUMP : if do not exist such file, will create one +*/ +class CSVTool{ +public: + CSVTool(std::string fileName, FileType type = FileType::READ_WRITE, int precision = 6); + ~CSVTool(){_ioStream.close();} + + bool getLine(std::string label, std::vector &values); + template + bool getLineDirect(std::string label, Args&... values); + + void modifyLine(std::string label, std::vector &values, bool addNew); + template + void modifyLineDirect(std::string label, bool addNew, Args&... values); + + void readFile(); + void saveFile(); + + bool _hasFile; +private: + std::string _fileName; + std::fstream _ioStream; + int _precision; + std::string _lineTemp; + std::map _labels; + std::vector _lines; + +}; + +/*************************/ +/* CSVLine */ +/*************************/ +// CSVLine::CSVLine(std::string lineTemp, std::streampos filePos) +// :_filePos(filePos){ + +// // std::cout << lineTemp << std::endl; +// } + +inline CSVLine::CSVLine(std::string lineTemp){ + // delete all spaces + lineTemp.erase(std::remove(lineTemp.begin(), lineTemp.end(), ' '), lineTemp.end()); + + std::stringstream ss(lineTemp); + std::string stringTemp; + + std::getline(ss, _label, ','); + + while(std::getline(ss, stringTemp, ',')){ + _values.push_back(stod(stringTemp)); + } + + // std::cout << "**********" << std::endl; + // std::cout << "_label: " << _label << std::fixed << std::setprecision(3) << std::endl; + // for(int i(0); i<_values.size(); ++i){ + // std::cout << _values.at(i) << ",,, "; + // } + // std::cout << std::endl; +} + +inline CSVLine::CSVLine(std::string label, std::vector values) + :_label(label), _values(values){ + +} + +inline void CSVLine::changeValue(std::vector values){ + if(values.size() != _values.size()){ + std::cout << "[WARNING] CSVLine::changeValue, the size changed" << std::endl; + } + _values = values; +} + +inline void CSVLine::getValues(std::vector &values){ + values = _values; +} + +inline void CSVLine::writeAtEnd(std::fstream &ioStream){ + ioStream << _label << ", "; + + for(int i(0); i<_values.size(); ++i){ + ioStream << _values.at(i) << ", "; + } + + ioStream << std::endl; +} + + +/*************************/ +/* CSVTool */ +/*************************/ +inline CSVTool::CSVTool(std::string fileName, FileType type, int precision) + : _fileName(fileName), _precision(precision){ + + if(type == FileType::READ_WRITE){ + _ioStream.open(_fileName, std::fstream::ate | std::fstream::in | std::fstream::out); + + if(!_ioStream.is_open()){ + std::cout << "[ERROR] CSVTool open file: " << fileName << " failed!" << std::endl; + // exit(-1); + _hasFile = false; + }else{ + readFile(); + _hasFile = true; + } + + } + else if(type == FileType::CLEAR_DUMP){ + _ioStream.open(_fileName, std::fstream::out); + } + +} + +inline void CSVTool::readFile(){ + if(!_ioStream.is_open()){ + // _ioStream.open(_fileName, std::fstream::ate | std::fstream::in | std::fstream::out); + std::cout << "[ERROR] CSVTool::readFile, file: " << _fileName << " has not been opened!" << std::endl; + return; + } + + _lines.clear(); + _labels.clear(); + + _ioStream.seekg(0, std::fstream::beg); + size_t lineNum = 0; + while(_ioStream && _ioStream.tellg() != std::fstream::end && getline(_ioStream, _lineTemp)){ + _lines.push_back( new CSVLine(_lineTemp) ); + + if(_labels.count(_lines.at(lineNum)->getLabel()) == 0){ + _labels.insert(std::pair(_lines.at(lineNum)->getLabel(), lineNum)); + ++lineNum; + }else{ + std::cout << "[ERROR] CSVTool::readFile, the label " + << _lines.at(lineNum)->getLabel() << " is repeated" << std::endl; + exit(-1); + } + } +} + +inline bool CSVTool::getLine(std::string label, std::vector &values){ + if(_labels.count(label) == 0){ + std::cout << "[ERROR] No such label: " << label << std::endl; + return false; + }else{ + _lines.at(_labels[label])->getValues(values); + return true; + } +} + +template +inline bool CSVTool::getLineDirect(std::string label, Args&... values){ + std::vector vec; + if(getLine(label, vec)){ + typeTrans::extractVector(vec, values...); + return true; + }else{ + return false; + } +} + +template +inline void CSVTool::modifyLineDirect(std::string label, bool addNew, Args&... values){ + std::vector vec; + typeTrans::combineToVector(vec, values...); + +// std::cout << "CSVTool::modifyLineDirect------" << std::endl; +// std::cout << "label: " << label << std::endl; +// std::cout << "vec: "; +// for(int i(0); iwriteAtEnd(_ioStream); + } + + _ioStream.close(); + _ioStream.open(_fileName, std::fstream::ate | std::fstream::in | std::fstream::out); +} + +inline void CSVTool::modifyLine(std::string label, std::vector &values, bool addNew =false){ + if(_labels.count(label) == 0){ + if(addNew){ + _labels.insert(std::pair(label, _labels.size())); + _lines.push_back(new CSVLine(label, values)); + }else{ + std::cout << "[ERROR] CSVTool::modifyLine, label " << label << "does not exist" << std::endl; + exit(-1); + } + }else{ + _lines.at(_labels[label])->changeValue(values); + } +} + + #endif // CSVTOOL_H \ No newline at end of file diff --git a/include/common/utilities/loop.h b/include/common/utilities/loop.h old mode 100644 new mode 100755 diff --git a/include/common/utilities/typeTrans.h b/include/common/utilities/typeTrans.h index 0f422e8..8096676 100755 --- a/include/common/utilities/typeTrans.h +++ b/include/common/utilities/typeTrans.h @@ -1,75 +1,75 @@ -#ifndef TYPETRANS_H -#define TYPETRANS_H - -#include -#include -#include - -namespace typeTrans{ - -inline void addValue(std::vector &vec, double value){ - vec.push_back(value); -} - -inline double getValue(std::vector &vec, double value){ - value = vec.at(0); - std::vector::iterator begin = vec.begin(); - vec.erase(begin); - - return value; -} - -inline void addValue(std::vector &vec, Eigen::MatrixXd value){ - for(int i(0); i &vec, Eigen::MatrixXd value){ - std::vector::iterator begin = vec.begin(); - std::vector::iterator end = begin; - - for(int i(0); i -inline void combineToVector(std::vector &vec, T value){ - addValue(vec, value); -} - -template -inline void combineToVector(std::vector &vec, const T t, const Args... rest){ - combineToVector(vec, t); - - combineToVector(vec, rest...); -} - - -/* extract different type variables from vector */ -template -inline void extractVector(std::vector &vec, T &value){ - value = getValue(vec, value); -} - -template -inline void extractVector(std::vector &vec, T &t, Args&... rest){ - extractVector(vec, t); - - extractVector(vec, rest...); -} - -} - +#ifndef TYPETRANS_H +#define TYPETRANS_H + +#include +#include +#include + +namespace typeTrans{ + +inline void addValue(std::vector &vec, double value){ + vec.push_back(value); +} + +inline double getValue(std::vector &vec, double value){ + value = vec.at(0); + std::vector::iterator begin = vec.begin(); + vec.erase(begin); + + return value; +} + +inline void addValue(std::vector &vec, Eigen::MatrixXd value){ + for(int i(0); i &vec, Eigen::MatrixXd value){ + std::vector::iterator begin = vec.begin(); + std::vector::iterator end = begin; + + for(int i(0); i +inline void combineToVector(std::vector &vec, T value){ + addValue(vec, value); +} + +template +inline void combineToVector(std::vector &vec, const T t, const Args... rest){ + combineToVector(vec, t); + + combineToVector(vec, rest...); +} + + +/* extract different type variables from vector */ +template +inline void extractVector(std::vector &vec, T &value){ + value = getValue(vec, value); +} + +template +inline void extractVector(std::vector &vec, T &t, Args&... rest){ + extractVector(vec, t); + + extractVector(vec, rest...); +} + +} + #endif // TYPETRANS_H \ No newline at end of file diff --git a/include/control/CtrlComponents.h b/include/control/CtrlComponents.h index 6b4e242..9829ba0 100755 --- a/include/control/CtrlComponents.h +++ b/include/control/CtrlComponents.h @@ -1,53 +1,53 @@ -#ifndef CTRLCOMPONENTS_H -#define CTRLCOMPONENTS_H - -#include -#include -#include "common/utilities/loop.h" -#include "message/arm_common.h" -#include "message/LowlevelCmd.h" -#include "message/LowlevelState.h" -#include "common/utilities/CSVTool.h" -#include "model/ArmModel.h" -#include "interface/IOUDP.h" -#include "interface/IOROS.h" -#include "control/armSDK.h" - -using namespace std; - -struct CtrlComponents{ -public: - CtrlComponents(int argc, char**argv); - ~CtrlComponents(); - - std::string armConfigPath; - CmdPanel *cmdPanel; - IOInterface *ioInter; - Z1Model *armModel; - CSVTool *stateCSV; - - SendCmd sendCmd; // cmd that receive from SDK - RecvState recvState;// state that send to SDK - - //config - double dt; - bool *running; - Control ctrl = Control::SDK; - bool hasGripper; - bool isCollisionOpen; - double collisionTLimit; - bool isPlot; - int trajChoose = 1; - size_t armType = 36; - - void geneObj(); - void writeData(); -private: - void configProcess(int argc, char** argv); - - std::string ctrl_IP; - uint ctrl_port; - double _loadWeight; -}; - +#ifndef CTRLCOMPONENTS_H +#define CTRLCOMPONENTS_H + +#include +#include +#include "common/utilities/loop.h" +#include "message/arm_common.h" +#include "message/LowlevelCmd.h" +#include "message/LowlevelState.h" +#include "common/utilities/CSVTool.h" +#include "model/ArmModel.h" +#include "interface/IOUDP.h" +#include "interface/IOROS.h" +#include "control/armSDK.h" + +using namespace std; + +struct CtrlComponents{ +public: + CtrlComponents(int argc, char**argv); + ~CtrlComponents(); + + std::string armConfigPath; + CmdPanel *cmdPanel; + IOInterface *ioInter; + Z1Model *armModel; + CSVTool *stateCSV; + + SendCmd sendCmd; // cmd that receive from SDK + RecvState recvState;// state that send to SDK + + //config + double dt; + bool *running; + Control ctrl = Control::SDK; + bool hasGripper; + bool isCollisionOpen; + double collisionTLimit; + bool isPlot; + int trajChoose = 1; + size_t armType = 36; + + void geneObj(); + void writeData(); +private: + void configProcess(int argc, char** argv); + + std::string ctrl_IP; + uint ctrl_port; + double _loadWeight; +}; + #endif // CTRLCOMPONENTS_H \ No newline at end of file diff --git a/include/interface/IOInterface.h b/include/interface/IOInterface.h index 9af2a71..444471d 100755 --- a/include/interface/IOInterface.h +++ b/include/interface/IOInterface.h @@ -1,28 +1,28 @@ -#ifndef IOINTERFACE_H -#define IOINTERFACE_H - -#include -#include "message/LowlevelCmd.h" -#include "message/LowlevelState.h" -#include "control/keyboard.h" -#include "common/math/robotics.h" - -class IOInterface{ -public: - IOInterface(){} - ~IOInterface(){ - delete lowCmd; - delete lowState; - }; - virtual bool sendRecv(const LowlevelCmd *cmd, LowlevelState *state) = 0; - virtual bool calibration(){return false;}; - bool checkGripper(){return hasGripper;}; - LowlevelCmd *lowCmd; - LowlevelState *lowState; - virtual bool isDisconnect(){ return false;}; - bool hasErrorState; -protected: - bool hasGripper; -}; - +#ifndef IOINTERFACE_H +#define IOINTERFACE_H + +#include +#include "message/LowlevelCmd.h" +#include "message/LowlevelState.h" +#include "control/keyboard.h" +#include "common/math/robotics.h" + +class IOInterface{ +public: + IOInterface(){} + ~IOInterface(){ + delete lowCmd; + delete lowState; + }; + virtual bool sendRecv(const LowlevelCmd *cmd, LowlevelState *state) = 0; + virtual bool calibration(){return false;}; + bool checkGripper(){return hasGripper;}; + LowlevelCmd *lowCmd; + LowlevelState *lowState; + virtual bool isDisconnect(){ return false;}; + bool hasErrorState; +protected: + bool hasGripper; +}; + #endif //IOINTERFACE_H \ No newline at end of file diff --git a/include/interface/IOROS.h b/include/interface/IOROS.h old mode 100755 new mode 100644 diff --git a/include/interface/IOUDP.h b/include/interface/IOUDP.h index 0b4fa05..1164ce5 100644 --- a/include/interface/IOUDP.h +++ b/include/interface/IOUDP.h @@ -1,26 +1,26 @@ -#ifndef IOUDP_H -#define IOUDP_H - -#include "interface/IOInterface.h" - -class IOUDP : public IOInterface{ -public: - IOUDP(const char* IP, uint port, size_t timeOutUs = 100000, bool showInfo = true); - ~IOUDP(); - - bool sendRecv(const LowlevelCmd *cmd, LowlevelState *state); - bool calibration(); - bool isDisconnect(){ return _ioPort->isDisConnect;} -private: - IOPort *_ioPort; - - UDPSendCmd _cmd; - UDPRecvState _state; - UDPRecvStateOld _stateOld; - size_t _motorNum; - size_t _jointNum; - uint8_t _singleState; - uint8_t _selfCheck[10]; -}; - +#ifndef IOUDP_H +#define IOUDP_H + +#include "interface/IOInterface.h" + +class IOUDP : public IOInterface{ +public: + IOUDP(const char* IP, uint port, size_t timeOutUs = 100000, bool showInfo = true); + ~IOUDP(); + + bool sendRecv(const LowlevelCmd *cmd, LowlevelState *state); + bool calibration(); + bool isDisconnect(){ return _ioPort->isDisConnect;} +private: + IOPort *_ioPort; + + UDPSendCmd _cmd; + UDPRecvState _state; + UDPRecvStateOld _stateOld; + size_t _motorNum; + size_t _jointNum; + uint8_t _singleState; + uint8_t _selfCheck[10]; +}; + #endif // IOUDP_H \ No newline at end of file diff --git a/include/message/LowlevelCmd.h b/include/message/LowlevelCmd.h index ac8ae44..24bda49 100755 --- a/include/message/LowlevelCmd.h +++ b/include/message/LowlevelCmd.h @@ -1,56 +1,56 @@ -#ifndef LOWLEVELCMD_H -#define LOWLEVELCMD_H - -#include "common/math/mathTypes.h" -#include "common/math/mathTools.h" -#include -#include - -struct LowlevelCmd{ -public: - std::vector q; - std::vector dq; - std::vector tau; - std::vector kp; - std::vector kd; - - std::vector> q_data; - std::vector> dq_data; - std::vector> tauf_data; - std::vector> tau_data; - - LowlevelCmd(); - ~LowlevelCmd(){} - - void setZeroDq(); - void setZeroTau(); - void setZeroKp(); - void setZeroKd(); - void setQ(VecX qInput); - void setQd(VecX qDInput); - void setTau(VecX tauInput); - - void setControlGain(); - void setControlGain(std::vector KP, std::vector KW); - void setPassive(); - - void setGripperGain(); - void setGripperGain(float KP, float KW); - void setGripperZeroGain(); - void setGripperQ(double qInput); - double getGripperQ(); - void setGripperQd(double qdInput); - double getGripperQd(); - void setGripperTau(double tauInput); - double getGripperTau(); - - Vec6 getQ(); - Vec6 getQd(); - - void resizeGripper(); -private: - size_t _dof = 6; -}; - - -#endif //LOWLEVELCMD_H +#ifndef LOWLEVELCMD_H +#define LOWLEVELCMD_H + +#include "common/math/mathTypes.h" +#include "common/math/mathTools.h" +#include +#include + +struct LowlevelCmd{ +public: + std::vector q; + std::vector dq; + std::vector tau; + std::vector kp; + std::vector kd; + + std::vector> q_data; + std::vector> dq_data; + std::vector> tauf_data; + std::vector> tau_data; + + LowlevelCmd(); + ~LowlevelCmd(){} + + void setZeroDq(); + void setZeroTau(); + void setZeroKp(); + void setZeroKd(); + void setQ(VecX qInput); + void setQd(VecX qDInput); + void setTau(VecX tauInput); + + void setControlGain(); + void setControlGain(std::vector KP, std::vector KW); + void setPassive(); + + void setGripperGain(); + void setGripperGain(float KP, float KW); + void setGripperZeroGain(); + void setGripperQ(double qInput); + double getGripperQ(); + void setGripperQd(double qdInput); + double getGripperQd(); + void setGripperTau(double tauInput); + double getGripperTau(); + + Vec6 getQ(); + Vec6 getQd(); + + void resizeGripper(); +private: + size_t _dof = 6; +}; + + +#endif //LOWLEVELCMD_H diff --git a/include/message/LowlevelState.h b/include/message/LowlevelState.h index 5a60dfd..935a47d 100755 --- a/include/message/LowlevelState.h +++ b/include/message/LowlevelState.h @@ -1,61 +1,61 @@ -#ifndef LOWLEVELSTATE_HPP -#define LOWLEVELSTATE_HPP - -#include -#include -#include "common/math/mathTools.h" -#include "common/enumClass.h" -#include "common/math/Filter.h" - -struct LowlevelState{ -public: - LowlevelState(double dt); - ~LowlevelState(); - - std::vector q; - std::vector dq; - std::vector ddq; - std::vector tau; - - std::vector> q_data; - std::vector> dq_data; - std::vector> ddq_data; - std::vector> tau_data; - - std::vector temperature; - std::vector errorstate; - std::vector isMotorConnected; - - std::vector qFiltered; - std::vector dqFiltered; - std::vector ddqFiltered; - std::vector tauFiltered; - - LPFilter *qFilter; - LPFilter *dqFilter; - LPFilter *ddqFilter; - LPFilter *tauFilter; - - void resizeGripper(double dt); - void runFilter(); - bool checkError(); - Vec6 getQ(); - Vec6 getQd(); - Vec6 getQdd(); - Vec6 getTau(); - Vec6 getQFiltered(); - Vec6 getQdFiltered(); - Vec6 getQddFiltered(); - Vec6 getTauFiltered(); - double getGripperQ(); - double getGripperQd(); - double getGripperTau(); - double getGripperTauFiltered(); -private: - size_t _dof = 6; - int temporatureLimit = 80.0;// centigrade - std::vector _isMotorConnectedCnt; - std::vector _isMotorLostConnection; -}; - -#endif //LOWLEVELSTATE_HPP +#ifndef LOWLEVELSTATE_HPP +#define LOWLEVELSTATE_HPP + +#include +#include +#include "common/math/mathTools.h" +#include "common/enumClass.h" +#include "common/math/Filter.h" + +struct LowlevelState{ +public: + LowlevelState(double dt); + ~LowlevelState(); + + std::vector q; + std::vector dq; + std::vector ddq; + std::vector tau; + + std::vector> q_data; + std::vector> dq_data; + std::vector> ddq_data; + std::vector> tau_data; + + std::vector temperature; + std::vector errorstate; + std::vector isMotorConnected; + + std::vector qFiltered; + std::vector dqFiltered; + std::vector ddqFiltered; + std::vector tauFiltered; + + LPFilter *qFilter; + LPFilter *dqFilter; + LPFilter *ddqFilter; + LPFilter *tauFilter; + + void resizeGripper(double dt); + void runFilter(); + bool checkError(); + Vec6 getQ(); + Vec6 getQd(); + Vec6 getQdd(); + Vec6 getTau(); + Vec6 getQFiltered(); + Vec6 getQdFiltered(); + Vec6 getQddFiltered(); + Vec6 getTauFiltered(); + double getGripperQ(); + double getGripperQd(); + double getGripperTau(); + double getGripperTauFiltered(); +private: + size_t _dof = 6; + int temporatureLimit = 80.0;// centigrade + std::vector _isMotorConnectedCnt; + std::vector _isMotorLostConnection; +}; + +#endif //LOWLEVELSTATE_HPP diff --git a/include/message/MotorCmd.h b/include/message/MotorCmd.h index 9efff2d..b5d90c9 100644 --- a/include/message/MotorCmd.h +++ b/include/message/MotorCmd.h @@ -1,261 +1,261 @@ -// Generated by gencpp from file unitree_legged_msgs/MotorCmd.msg -// DO NOT EDIT! - - -#ifndef UNITREE_LEGGED_MSGS_MESSAGE_MOTORCMD_H -#define UNITREE_LEGGED_MSGS_MESSAGE_MOTORCMD_H - - -#include -#include -#include - -#include -#include -#include -#include - - -namespace unitree_legged_msgs -{ -template -struct MotorCmd_ -{ - typedef MotorCmd_ Type; - - MotorCmd_() - : mode(0) - , q(0.0) - , dq(0.0) - , tau(0.0) - , Kp(0.0) - , Kd(0.0) - , reserve() { - reserve.assign(0); - } - MotorCmd_(const ContainerAllocator& _alloc) - : mode(0) - , q(0.0) - , dq(0.0) - , tau(0.0) - , Kp(0.0) - , Kd(0.0) - , reserve() { - (void)_alloc; - reserve.assign(0); - } - - - - typedef uint8_t _mode_type; - _mode_type mode; - - typedef float _q_type; - _q_type q; - - typedef float _dq_type; - _dq_type dq; - - typedef float _tau_type; - _tau_type tau; - - typedef float _Kp_type; - _Kp_type Kp; - - typedef float _Kd_type; - _Kd_type Kd; - - typedef boost::array _reserve_type; - _reserve_type reserve; - - - - - - typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd_ > Ptr; - typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd_ const> ConstPtr; - -}; // struct MotorCmd_ - -typedef ::unitree_legged_msgs::MotorCmd_ > MotorCmd; - -typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd > MotorCmdPtr; -typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd const> MotorCmdConstPtr; - -// constants requiring out of line definition - - - -template -std::ostream& operator<<(std::ostream& s, const ::unitree_legged_msgs::MotorCmd_ & v) -{ -ros::message_operations::Printer< ::unitree_legged_msgs::MotorCmd_ >::stream(s, "", v); -return s; -} - - -template -bool operator==(const ::unitree_legged_msgs::MotorCmd_ & lhs, const ::unitree_legged_msgs::MotorCmd_ & rhs) -{ - return lhs.mode == rhs.mode && - lhs.q == rhs.q && - lhs.dq == rhs.dq && - lhs.tau == rhs.tau && - lhs.Kp == rhs.Kp && - lhs.Kd == rhs.Kd && - lhs.reserve == rhs.reserve; -} - -template -bool operator!=(const ::unitree_legged_msgs::MotorCmd_ & lhs, const ::unitree_legged_msgs::MotorCmd_ & rhs) -{ - return !(lhs == rhs); -} - - -} // namespace unitree_legged_msgs - -namespace ros -{ -namespace message_traits -{ - - - - - -template -struct IsFixedSize< ::unitree_legged_msgs::MotorCmd_ > - : TrueType - { }; - -template -struct IsFixedSize< ::unitree_legged_msgs::MotorCmd_ const> - : TrueType - { }; - -template -struct IsMessage< ::unitree_legged_msgs::MotorCmd_ > - : TrueType - { }; - -template -struct IsMessage< ::unitree_legged_msgs::MotorCmd_ const> - : TrueType - { }; - -template -struct HasHeader< ::unitree_legged_msgs::MotorCmd_ > - : FalseType - { }; - -template -struct HasHeader< ::unitree_legged_msgs::MotorCmd_ const> - : FalseType - { }; - - -template -struct MD5Sum< ::unitree_legged_msgs::MotorCmd_ > -{ - static const char* value() - { - return "bbb3b7d91319c3a1b99055f0149ba221"; - } - - static const char* value(const ::unitree_legged_msgs::MotorCmd_&) { return value(); } - static const uint64_t static_value1 = 0xbbb3b7d91319c3a1ULL; - static const uint64_t static_value2 = 0xb99055f0149ba221ULL; -}; - -template -struct DataType< ::unitree_legged_msgs::MotorCmd_ > -{ - static const char* value() - { - return "unitree_legged_msgs/MotorCmd"; - } - - static const char* value(const ::unitree_legged_msgs::MotorCmd_&) { return value(); } -}; - -template -struct Definition< ::unitree_legged_msgs::MotorCmd_ > -{ - static const char* value() - { - return "uint8 mode # motor target mode\n" -"float32 q # motor target position\n" -"float32 dq # motor target velocity\n" -"float32 tau # motor target torque\n" -"float32 Kp # motor spring stiffness coefficient\n" -"float32 Kd # motor damper coefficient\n" -"uint32[3] reserve # motor target torque\n" -; - } - - static const char* value(const ::unitree_legged_msgs::MotorCmd_&) { return value(); } -}; - -} // namespace message_traits -} // namespace ros - -namespace ros -{ -namespace serialization -{ - - template struct Serializer< ::unitree_legged_msgs::MotorCmd_ > - { - template inline static void allInOne(Stream& stream, T m) - { - stream.next(m.mode); - stream.next(m.q); - stream.next(m.dq); - stream.next(m.tau); - stream.next(m.Kp); - stream.next(m.Kd); - stream.next(m.reserve); - } - - ROS_DECLARE_ALLINONE_SERIALIZER - }; // struct MotorCmd_ - -} // namespace serialization -} // namespace ros - -namespace ros -{ -namespace message_operations -{ - -template -struct Printer< ::unitree_legged_msgs::MotorCmd_ > -{ - template static void stream(Stream& s, const std::string& indent, const ::unitree_legged_msgs::MotorCmd_& v) - { - s << indent << "mode: "; - Printer::stream(s, indent + " ", v.mode); - s << indent << "q: "; - Printer::stream(s, indent + " ", v.q); - s << indent << "dq: "; - Printer::stream(s, indent + " ", v.dq); - s << indent << "tau: "; - Printer::stream(s, indent + " ", v.tau); - s << indent << "Kp: "; - Printer::stream(s, indent + " ", v.Kp); - s << indent << "Kd: "; - Printer::stream(s, indent + " ", v.Kd); - s << indent << "reserve[]" << std::endl; - for (size_t i = 0; i < v.reserve.size(); ++i) - { - s << indent << " reserve[" << i << "]: "; - Printer::stream(s, indent + " ", v.reserve[i]); - } - } -}; - -} // namespace message_operations -} // namespace ros - -#endif // UNITREE_LEGGED_MSGS_MESSAGE_MOTORCMD_H +// Generated by gencpp from file unitree_legged_msgs/MotorCmd.msg +// DO NOT EDIT! + + +#ifndef UNITREE_LEGGED_MSGS_MESSAGE_MOTORCMD_H +#define UNITREE_LEGGED_MSGS_MESSAGE_MOTORCMD_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace unitree_legged_msgs +{ +template +struct MotorCmd_ +{ + typedef MotorCmd_ Type; + + MotorCmd_() + : mode(0) + , q(0.0) + , dq(0.0) + , tau(0.0) + , Kp(0.0) + , Kd(0.0) + , reserve() { + reserve.assign(0); + } + MotorCmd_(const ContainerAllocator& _alloc) + : mode(0) + , q(0.0) + , dq(0.0) + , tau(0.0) + , Kp(0.0) + , Kd(0.0) + , reserve() { + (void)_alloc; + reserve.assign(0); + } + + + + typedef uint8_t _mode_type; + _mode_type mode; + + typedef float _q_type; + _q_type q; + + typedef float _dq_type; + _dq_type dq; + + typedef float _tau_type; + _tau_type tau; + + typedef float _Kp_type; + _Kp_type Kp; + + typedef float _Kd_type; + _Kd_type Kd; + + typedef boost::array _reserve_type; + _reserve_type reserve; + + + + + + typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd_ > Ptr; + typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd_ const> ConstPtr; + +}; // struct MotorCmd_ + +typedef ::unitree_legged_msgs::MotorCmd_ > MotorCmd; + +typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd > MotorCmdPtr; +typedef boost::shared_ptr< ::unitree_legged_msgs::MotorCmd const> MotorCmdConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::unitree_legged_msgs::MotorCmd_ & v) +{ +ros::message_operations::Printer< ::unitree_legged_msgs::MotorCmd_ >::stream(s, "", v); +return s; +} + + +template +bool operator==(const ::unitree_legged_msgs::MotorCmd_ & lhs, const ::unitree_legged_msgs::MotorCmd_ & rhs) +{ + return lhs.mode == rhs.mode && + lhs.q == rhs.q && + lhs.dq == rhs.dq && + lhs.tau == rhs.tau && + lhs.Kp == rhs.Kp && + lhs.Kd == rhs.Kd && + lhs.reserve == rhs.reserve; +} + +template +bool operator!=(const ::unitree_legged_msgs::MotorCmd_ & lhs, const ::unitree_legged_msgs::MotorCmd_ & rhs) +{ + return !(lhs == rhs); +} + + +} // namespace unitree_legged_msgs + +namespace ros +{ +namespace message_traits +{ + + + + + +template +struct IsFixedSize< ::unitree_legged_msgs::MotorCmd_ > + : TrueType + { }; + +template +struct IsFixedSize< ::unitree_legged_msgs::MotorCmd_ const> + : TrueType + { }; + +template +struct IsMessage< ::unitree_legged_msgs::MotorCmd_ > + : TrueType + { }; + +template +struct IsMessage< ::unitree_legged_msgs::MotorCmd_ const> + : TrueType + { }; + +template +struct HasHeader< ::unitree_legged_msgs::MotorCmd_ > + : FalseType + { }; + +template +struct HasHeader< ::unitree_legged_msgs::MotorCmd_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::unitree_legged_msgs::MotorCmd_ > +{ + static const char* value() + { + return "bbb3b7d91319c3a1b99055f0149ba221"; + } + + static const char* value(const ::unitree_legged_msgs::MotorCmd_&) { return value(); } + static const uint64_t static_value1 = 0xbbb3b7d91319c3a1ULL; + static const uint64_t static_value2 = 0xb99055f0149ba221ULL; +}; + +template +struct DataType< ::unitree_legged_msgs::MotorCmd_ > +{ + static const char* value() + { + return "unitree_legged_msgs/MotorCmd"; + } + + static const char* value(const ::unitree_legged_msgs::MotorCmd_&) { return value(); } +}; + +template +struct Definition< ::unitree_legged_msgs::MotorCmd_ > +{ + static const char* value() + { + return "uint8 mode # motor target mode\n" +"float32 q # motor target position\n" +"float32 dq # motor target velocity\n" +"float32 tau # motor target torque\n" +"float32 Kp # motor spring stiffness coefficient\n" +"float32 Kd # motor damper coefficient\n" +"uint32[3] reserve # motor target torque\n" +; + } + + static const char* value(const ::unitree_legged_msgs::MotorCmd_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::unitree_legged_msgs::MotorCmd_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.mode); + stream.next(m.q); + stream.next(m.dq); + stream.next(m.tau); + stream.next(m.Kp); + stream.next(m.Kd); + stream.next(m.reserve); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MotorCmd_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::unitree_legged_msgs::MotorCmd_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::unitree_legged_msgs::MotorCmd_& v) + { + s << indent << "mode: "; + Printer::stream(s, indent + " ", v.mode); + s << indent << "q: "; + Printer::stream(s, indent + " ", v.q); + s << indent << "dq: "; + Printer::stream(s, indent + " ", v.dq); + s << indent << "tau: "; + Printer::stream(s, indent + " ", v.tau); + s << indent << "Kp: "; + Printer::stream(s, indent + " ", v.Kp); + s << indent << "Kd: "; + Printer::stream(s, indent + " ", v.Kd); + s << indent << "reserve[]" << std::endl; + for (size_t i = 0; i < v.reserve.size(); ++i) + { + s << indent << " reserve[" << i << "]: "; + Printer::stream(s, indent + " ", v.reserve[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // UNITREE_LEGGED_MSGS_MESSAGE_MOTORCMD_H diff --git a/include/message/MotorState.h b/include/message/MotorState.h index e7183e0..8dcfd42 100644 --- a/include/message/MotorState.h +++ b/include/message/MotorState.h @@ -1,291 +1,291 @@ -// Generated by gencpp from file unitree_legged_msgs/MotorState.msg -// DO NOT EDIT! - - -#ifndef UNITREE_LEGGED_MSGS_MESSAGE_MOTORSTATE_H -#define UNITREE_LEGGED_MSGS_MESSAGE_MOTORSTATE_H - - -#include -#include -#include - -#include -#include -#include -#include - - -namespace unitree_legged_msgs -{ -template -struct MotorState_ -{ - typedef MotorState_ Type; - - MotorState_() - : mode(0) - , q(0.0) - , dq(0.0) - , ddq(0.0) - , tauEst(0.0) - , q_raw(0.0) - , dq_raw(0.0) - , ddq_raw(0.0) - , temperature(0) - , reserve() { - reserve.assign(0); - } - MotorState_(const ContainerAllocator& _alloc) - : mode(0) - , q(0.0) - , dq(0.0) - , ddq(0.0) - , tauEst(0.0) - , q_raw(0.0) - , dq_raw(0.0) - , ddq_raw(0.0) - , temperature(0) - , reserve() { - (void)_alloc; - reserve.assign(0); - } - - - - typedef uint8_t _mode_type; - _mode_type mode; - - typedef float _q_type; - _q_type q; - - typedef float _dq_type; - _dq_type dq; - - typedef float _ddq_type; - _ddq_type ddq; - - typedef float _tauEst_type; - _tauEst_type tauEst; - - typedef float _q_raw_type; - _q_raw_type q_raw; - - typedef float _dq_raw_type; - _dq_raw_type dq_raw; - - typedef float _ddq_raw_type; - _ddq_raw_type ddq_raw; - - typedef int8_t _temperature_type; - _temperature_type temperature; - - typedef boost::array _reserve_type; - _reserve_type reserve; - - - - - - typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState_ > Ptr; - typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState_ const> ConstPtr; - -}; // struct MotorState_ - -typedef ::unitree_legged_msgs::MotorState_ > MotorState; - -typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState > MotorStatePtr; -typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState const> MotorStateConstPtr; - -// constants requiring out of line definition - - - -template -std::ostream& operator<<(std::ostream& s, const ::unitree_legged_msgs::MotorState_ & v) -{ -ros::message_operations::Printer< ::unitree_legged_msgs::MotorState_ >::stream(s, "", v); -return s; -} - - -template -bool operator==(const ::unitree_legged_msgs::MotorState_ & lhs, const ::unitree_legged_msgs::MotorState_ & rhs) -{ - return lhs.mode == rhs.mode && - lhs.q == rhs.q && - lhs.dq == rhs.dq && - lhs.ddq == rhs.ddq && - lhs.tauEst == rhs.tauEst && - lhs.q_raw == rhs.q_raw && - lhs.dq_raw == rhs.dq_raw && - lhs.ddq_raw == rhs.ddq_raw && - lhs.temperature == rhs.temperature && - lhs.reserve == rhs.reserve; -} - -template -bool operator!=(const ::unitree_legged_msgs::MotorState_ & lhs, const ::unitree_legged_msgs::MotorState_ & rhs) -{ - return !(lhs == rhs); -} - - -} // namespace unitree_legged_msgs - -namespace ros -{ -namespace message_traits -{ - - - - - -template -struct IsFixedSize< ::unitree_legged_msgs::MotorState_ > - : TrueType - { }; - -template -struct IsFixedSize< ::unitree_legged_msgs::MotorState_ const> - : TrueType - { }; - -template -struct IsMessage< ::unitree_legged_msgs::MotorState_ > - : TrueType - { }; - -template -struct IsMessage< ::unitree_legged_msgs::MotorState_ const> - : TrueType - { }; - -template -struct HasHeader< ::unitree_legged_msgs::MotorState_ > - : FalseType - { }; - -template -struct HasHeader< ::unitree_legged_msgs::MotorState_ const> - : FalseType - { }; - - -template -struct MD5Sum< ::unitree_legged_msgs::MotorState_ > -{ - static const char* value() - { - return "94c55ee3b7852be2bd437b20ce12a254"; - } - - static const char* value(const ::unitree_legged_msgs::MotorState_&) { return value(); } - static const uint64_t static_value1 = 0x94c55ee3b7852be2ULL; - static const uint64_t static_value2 = 0xbd437b20ce12a254ULL; -}; - -template -struct DataType< ::unitree_legged_msgs::MotorState_ > -{ - static const char* value() - { - return "unitree_legged_msgs/MotorState"; - } - - static const char* value(const ::unitree_legged_msgs::MotorState_&) { return value(); } -}; - -template -struct Definition< ::unitree_legged_msgs::MotorState_ > -{ - static const char* value() - { - return "uint8 mode # motor current mode \n" -"float32 q # motor current position(rad)\n" -"float32 dq # motor current speed(rad/s)\n" -"float32 ddq # motor current speed(rad/s)\n" -"float32 tauEst # current estimated output torque(N*m)\n" -"float32 q_raw # motor current position(rad)\n" -"float32 dq_raw # motor current speed(rad/s)\n" -"float32 ddq_raw # motor current speed(rad/s)\n" -"int8 temperature # motor temperature(slow conduction of temperature leads to lag)\n" -"uint32[2] reserve\n" -; - } - - static const char* value(const ::unitree_legged_msgs::MotorState_&) { return value(); } -}; - -} // namespace message_traits -} // namespace ros - -namespace ros -{ -namespace serialization -{ - - template struct Serializer< ::unitree_legged_msgs::MotorState_ > - { - template inline static void allInOne(Stream& stream, T m) - { - stream.next(m.mode); - stream.next(m.q); - stream.next(m.dq); - stream.next(m.ddq); - stream.next(m.tauEst); - stream.next(m.q_raw); - stream.next(m.dq_raw); - stream.next(m.ddq_raw); - stream.next(m.temperature); - stream.next(m.reserve); - } - - ROS_DECLARE_ALLINONE_SERIALIZER - }; // struct MotorState_ - -} // namespace serialization -} // namespace ros - -namespace ros -{ -namespace message_operations -{ - -template -struct Printer< ::unitree_legged_msgs::MotorState_ > -{ - template static void stream(Stream& s, const std::string& indent, const ::unitree_legged_msgs::MotorState_& v) - { - s << indent << "mode: "; - Printer::stream(s, indent + " ", v.mode); - s << indent << "q: "; - Printer::stream(s, indent + " ", v.q); - s << indent << "dq: "; - Printer::stream(s, indent + " ", v.dq); - s << indent << "ddq: "; - Printer::stream(s, indent + " ", v.ddq); - s << indent << "tauEst: "; - Printer::stream(s, indent + " ", v.tauEst); - s << indent << "q_raw: "; - Printer::stream(s, indent + " ", v.q_raw); - s << indent << "dq_raw: "; - Printer::stream(s, indent + " ", v.dq_raw); - s << indent << "ddq_raw: "; - Printer::stream(s, indent + " ", v.ddq_raw); - s << indent << "temperature: "; - Printer::stream(s, indent + " ", v.temperature); - s << indent << "reserve[]" << std::endl; - for (size_t i = 0; i < v.reserve.size(); ++i) - { - s << indent << " reserve[" << i << "]: "; - Printer::stream(s, indent + " ", v.reserve[i]); - } - } -}; - -} // namespace message_operations -} // namespace ros - -#endif // UNITREE_LEGGED_MSGS_MESSAGE_MOTORSTATE_H +// Generated by gencpp from file unitree_legged_msgs/MotorState.msg +// DO NOT EDIT! + + +#ifndef UNITREE_LEGGED_MSGS_MESSAGE_MOTORSTATE_H +#define UNITREE_LEGGED_MSGS_MESSAGE_MOTORSTATE_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace unitree_legged_msgs +{ +template +struct MotorState_ +{ + typedef MotorState_ Type; + + MotorState_() + : mode(0) + , q(0.0) + , dq(0.0) + , ddq(0.0) + , tauEst(0.0) + , q_raw(0.0) + , dq_raw(0.0) + , ddq_raw(0.0) + , temperature(0) + , reserve() { + reserve.assign(0); + } + MotorState_(const ContainerAllocator& _alloc) + : mode(0) + , q(0.0) + , dq(0.0) + , ddq(0.0) + , tauEst(0.0) + , q_raw(0.0) + , dq_raw(0.0) + , ddq_raw(0.0) + , temperature(0) + , reserve() { + (void)_alloc; + reserve.assign(0); + } + + + + typedef uint8_t _mode_type; + _mode_type mode; + + typedef float _q_type; + _q_type q; + + typedef float _dq_type; + _dq_type dq; + + typedef float _ddq_type; + _ddq_type ddq; + + typedef float _tauEst_type; + _tauEst_type tauEst; + + typedef float _q_raw_type; + _q_raw_type q_raw; + + typedef float _dq_raw_type; + _dq_raw_type dq_raw; + + typedef float _ddq_raw_type; + _ddq_raw_type ddq_raw; + + typedef int8_t _temperature_type; + _temperature_type temperature; + + typedef boost::array _reserve_type; + _reserve_type reserve; + + + + + + typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState_ > Ptr; + typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState_ const> ConstPtr; + +}; // struct MotorState_ + +typedef ::unitree_legged_msgs::MotorState_ > MotorState; + +typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState > MotorStatePtr; +typedef boost::shared_ptr< ::unitree_legged_msgs::MotorState const> MotorStateConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::unitree_legged_msgs::MotorState_ & v) +{ +ros::message_operations::Printer< ::unitree_legged_msgs::MotorState_ >::stream(s, "", v); +return s; +} + + +template +bool operator==(const ::unitree_legged_msgs::MotorState_ & lhs, const ::unitree_legged_msgs::MotorState_ & rhs) +{ + return lhs.mode == rhs.mode && + lhs.q == rhs.q && + lhs.dq == rhs.dq && + lhs.ddq == rhs.ddq && + lhs.tauEst == rhs.tauEst && + lhs.q_raw == rhs.q_raw && + lhs.dq_raw == rhs.dq_raw && + lhs.ddq_raw == rhs.ddq_raw && + lhs.temperature == rhs.temperature && + lhs.reserve == rhs.reserve; +} + +template +bool operator!=(const ::unitree_legged_msgs::MotorState_ & lhs, const ::unitree_legged_msgs::MotorState_ & rhs) +{ + return !(lhs == rhs); +} + + +} // namespace unitree_legged_msgs + +namespace ros +{ +namespace message_traits +{ + + + + + +template +struct IsFixedSize< ::unitree_legged_msgs::MotorState_ > + : TrueType + { }; + +template +struct IsFixedSize< ::unitree_legged_msgs::MotorState_ const> + : TrueType + { }; + +template +struct IsMessage< ::unitree_legged_msgs::MotorState_ > + : TrueType + { }; + +template +struct IsMessage< ::unitree_legged_msgs::MotorState_ const> + : TrueType + { }; + +template +struct HasHeader< ::unitree_legged_msgs::MotorState_ > + : FalseType + { }; + +template +struct HasHeader< ::unitree_legged_msgs::MotorState_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::unitree_legged_msgs::MotorState_ > +{ + static const char* value() + { + return "94c55ee3b7852be2bd437b20ce12a254"; + } + + static const char* value(const ::unitree_legged_msgs::MotorState_&) { return value(); } + static const uint64_t static_value1 = 0x94c55ee3b7852be2ULL; + static const uint64_t static_value2 = 0xbd437b20ce12a254ULL; +}; + +template +struct DataType< ::unitree_legged_msgs::MotorState_ > +{ + static const char* value() + { + return "unitree_legged_msgs/MotorState"; + } + + static const char* value(const ::unitree_legged_msgs::MotorState_&) { return value(); } +}; + +template +struct Definition< ::unitree_legged_msgs::MotorState_ > +{ + static const char* value() + { + return "uint8 mode # motor current mode \n" +"float32 q # motor current position(rad)\n" +"float32 dq # motor current speed(rad/s)\n" +"float32 ddq # motor current speed(rad/s)\n" +"float32 tauEst # current estimated output torque(N*m)\n" +"float32 q_raw # motor current position(rad)\n" +"float32 dq_raw # motor current speed(rad/s)\n" +"float32 ddq_raw # motor current speed(rad/s)\n" +"int8 temperature # motor temperature(slow conduction of temperature leads to lag)\n" +"uint32[2] reserve\n" +; + } + + static const char* value(const ::unitree_legged_msgs::MotorState_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::unitree_legged_msgs::MotorState_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.mode); + stream.next(m.q); + stream.next(m.dq); + stream.next(m.ddq); + stream.next(m.tauEst); + stream.next(m.q_raw); + stream.next(m.dq_raw); + stream.next(m.ddq_raw); + stream.next(m.temperature); + stream.next(m.reserve); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MotorState_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::unitree_legged_msgs::MotorState_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::unitree_legged_msgs::MotorState_& v) + { + s << indent << "mode: "; + Printer::stream(s, indent + " ", v.mode); + s << indent << "q: "; + Printer::stream(s, indent + " ", v.q); + s << indent << "dq: "; + Printer::stream(s, indent + " ", v.dq); + s << indent << "ddq: "; + Printer::stream(s, indent + " ", v.ddq); + s << indent << "tauEst: "; + Printer::stream(s, indent + " ", v.tauEst); + s << indent << "q_raw: "; + Printer::stream(s, indent + " ", v.q_raw); + s << indent << "dq_raw: "; + Printer::stream(s, indent + " ", v.dq_raw); + s << indent << "ddq_raw: "; + Printer::stream(s, indent + " ", v.ddq_raw); + s << indent << "temperature: "; + Printer::stream(s, indent + " ", v.temperature); + s << indent << "reserve[]" << std::endl; + for (size_t i = 0; i < v.reserve.size(); ++i) + { + s << indent << " reserve[" << i << "]: "; + Printer::stream(s, indent + " ", v.reserve[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // UNITREE_LEGGED_MSGS_MESSAGE_MOTORSTATE_H diff --git a/include/message/arm_common.h b/include/message/arm_common.h old mode 100644 new mode 100755 diff --git a/include/thirdparty/quadProgpp/Array.hh b/include/thirdparty/quadProgpp/Array.hh old mode 100644 new mode 100755 index 29e494d..53ab624 --- a/include/thirdparty/quadProgpp/Array.hh +++ b/include/thirdparty/quadProgpp/Array.hh @@ -1,2532 +1,2532 @@ -// $Id: Array.hh 249 2008-11-20 09:58:23Z schaerf $ -// This file is part of EasyLocalpp: a C++ Object-Oriented framework -// aimed at easing the development of Local Search algorithms. -// Copyright (C) 2001--2008 Andrea Schaerf, Luca Di Gaspero. -// -// This software may be modified and distributed under the terms -// of the MIT license. See the LICENSE file for details. - -#if !defined(_ARRAY_HH) -#define _ARRAY_HH - -#include -#include -#include -#include -#include -#include - -namespace quadprogpp { - -enum MType { DIAG }; - -template -class Vector -{ -public: - Vector(); - Vector(const unsigned int n); - Vector(const T& a, const unsigned int n); //initialize to constant value - Vector(const T* a, const unsigned int n); // Initialize to array - Vector(const Vector &rhs); // copy constructor - ~Vector(); // destructor - - inline void set(const T* a, const unsigned int n); - Vector extract(const std::set& indexes) const; - inline T& operator[](const unsigned int& i); //i-th element - inline const T& operator[](const unsigned int& i) const; - - inline unsigned int size() const; - inline void resize(const unsigned int n); - inline void resize(const T& a, const unsigned int n); - - Vector& operator=(const Vector& rhs); //assignment - Vector& operator=(const T& a); //assign a to every element - inline Vector& operator+=(const Vector& rhs); - inline Vector& operator-=(const Vector& rhs); - inline Vector& operator*=(const Vector& rhs); - inline Vector& operator/=(const Vector& rhs); - inline Vector& operator^=(const Vector& rhs); - inline Vector& operator+=(const T& a); - inline Vector& operator-=(const T& a); - inline Vector& operator*=(const T& a); - inline Vector& operator/=(const T& a); - inline Vector& operator^=(const T& a); -private: - unsigned int n; // size of array. upper index is n-1 - T* v; // storage for data -}; - -template -Vector::Vector() - : n(0), v(0) -{} - -template -Vector::Vector(const unsigned int n) - : v(new T[n]) -{ - this->n = n; -} - -template -Vector::Vector(const T& a, const unsigned int n) - : v(new T[n]) -{ - this->n = n; - for (unsigned int i = 0; i < n; i++) - v[i] = a; -} - -template -Vector::Vector(const T* a, const unsigned int n) - : v(new T[n]) -{ - this->n = n; - for (unsigned int i = 0; i < n; i++) - v[i] = *a++; -} - -template -Vector::Vector(const Vector& rhs) - : v(new T[rhs.n]) -{ - this->n = rhs.n; - for (unsigned int i = 0; i < n; i++) - v[i] = rhs[i]; -} - -template -Vector::~Vector() -{ - if (v != 0) - delete[] (v); -} - -template -void Vector::resize(const unsigned int n) -{ - if (n == this->n) - return; - if (v != 0) - delete[] (v); - v = new T[n]; - this->n = n; -} - -template -void Vector::resize(const T& a, const unsigned int n) -{ - resize(n); - for (unsigned int i = 0; i < n; i++) - v[i] = a; -} - - -template -inline Vector& Vector::operator=(const Vector& rhs) -// postcondition: normal assignment via copying has been performed; -// if vector and rhs were different sizes, vector -// has been resized to match the size of rhs -{ - if (this != &rhs) - { - resize(rhs.n); - for (unsigned int i = 0; i < n; i++) - v[i] = rhs[i]; - } - return *this; -} - -template -inline Vector & Vector::operator=(const T& a) //assign a to every element -{ - for (unsigned int i = 0; i < n; i++) - v[i] = a; - return *this; -} - -template -inline T & Vector::operator[](const unsigned int& i) //subscripting -{ - return v[i]; -} - -template -inline const T& Vector::operator[](const unsigned int& i) const //subscripting -{ - return v[i]; -} - -template -inline unsigned int Vector::size() const -{ - return n; -} - -template -inline void Vector::set(const T* a, unsigned int n) -{ - resize(n); - for (unsigned int i = 0; i < n; i++) - v[i] = a[i]; -} - -template -inline Vector Vector::extract(const std::set& indexes) const -{ - Vector tmp(indexes.size()); - unsigned int i = 0; - - for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) - { - if (*el >= n) - throw std::logic_error("Error extracting subvector: the indexes are out of vector bounds"); - tmp[i++] = v[*el]; - } - - return tmp; -} - -template -inline Vector& Vector::operator+=(const Vector& rhs) -{ - if (this->size() != rhs.size()) - throw std::logic_error("Operator+=: vectors have different sizes"); - for (unsigned int i = 0; i < n; i++) - v[i] += rhs[i]; - - return *this; -} - - -template -inline Vector& Vector::operator+=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - v[i] += a; - - return *this; -} - -template -inline Vector operator+(const Vector& rhs) -{ - return rhs; -} - -template -inline Vector operator+(const Vector& lhs, const Vector& rhs) -{ - if (lhs.size() != rhs.size()) - throw std::logic_error("Operator+: vectors have different sizes"); - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] + rhs[i]; - - return tmp; -} - -template -inline Vector operator+(const Vector& lhs, const T& a) -{ - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] + a; - - return tmp; -} - -template -inline Vector operator+(const T& a, const Vector& rhs) -{ - Vector tmp(rhs.size()); - for (unsigned int i = 0; i < rhs.size(); i++) - tmp[i] = a + rhs[i]; - - return tmp; -} - -template -inline Vector& Vector::operator-=(const Vector& rhs) -{ - if (this->size() != rhs.size()) - throw std::logic_error("Operator-=: vectors have different sizes"); - for (unsigned int i = 0; i < n; i++) - v[i] -= rhs[i]; - - return *this; -} - - -template -inline Vector& Vector::operator-=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - v[i] -= a; - - return *this; -} - -template -inline Vector operator-(const Vector& rhs) -{ - return (T)(-1) * rhs; -} - -template -inline Vector operator-(const Vector& lhs, const Vector& rhs) -{ - if (lhs.size() != rhs.size()) - throw std::logic_error("Operator-: vectors have different sizes"); - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] - rhs[i]; - - return tmp; -} - -template -inline Vector operator-(const Vector& lhs, const T& a) -{ - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] - a; - - return tmp; -} - -template -inline Vector operator-(const T& a, const Vector& rhs) -{ - Vector tmp(rhs.size()); - for (unsigned int i = 0; i < rhs.size(); i++) - tmp[i] = a - rhs[i]; - - return tmp; -} - -template -inline Vector& Vector::operator*=(const Vector& rhs) -{ - if (this->size() != rhs.size()) - throw std::logic_error("Operator*=: vectors have different sizes"); - for (unsigned int i = 0; i < n; i++) - v[i] *= rhs[i]; - - return *this; -} - - -template -inline Vector& Vector::operator*=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - v[i] *= a; - - return *this; -} - -template -inline Vector operator*(const Vector& lhs, const Vector& rhs) -{ - if (lhs.size() != rhs.size()) - throw std::logic_error("Operator*: vectors have different sizes"); - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] * rhs[i]; - - return tmp; -} - -template -inline Vector operator*(const Vector& lhs, const T& a) -{ - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] * a; - - return tmp; -} - -template -inline Vector operator*(const T& a, const Vector& rhs) -{ - Vector tmp(rhs.size()); - for (unsigned int i = 0; i < rhs.size(); i++) - tmp[i] = a * rhs[i]; - - return tmp; -} - -template -inline Vector& Vector::operator/=(const Vector& rhs) -{ - if (this->size() != rhs.size()) - throw std::logic_error("Operator/=: vectors have different sizes"); - for (unsigned int i = 0; i < n; i++) - v[i] /= rhs[i]; - - return *this; -} - - -template -inline Vector& Vector::operator/=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - v[i] /= a; - - return *this; -} - -template -inline Vector operator/(const Vector& lhs, const Vector& rhs) -{ - if (lhs.size() != rhs.size()) - throw std::logic_error("Operator/: vectors have different sizes"); - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] / rhs[i]; - - return tmp; -} - -template -inline Vector operator/(const Vector& lhs, const T& a) -{ - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = lhs[i] / a; - - return tmp; -} - -template -inline Vector operator/(const T& a, const Vector& rhs) -{ - Vector tmp(rhs.size()); - for (unsigned int i = 0; i < rhs.size(); i++) - tmp[i] = a / rhs[i]; - - return tmp; -} - -template -inline Vector operator^(const Vector& lhs, const Vector& rhs) -{ - if (lhs.size() != rhs.size()) - throw std::logic_error("Operator^: vectors have different sizes"); - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = pow(lhs[i], rhs[i]); - - return tmp; -} - -template -inline Vector operator^(const Vector& lhs, const T& a) -{ - Vector tmp(lhs.size()); - for (unsigned int i = 0; i < lhs.size(); i++) - tmp[i] = pow(lhs[i], a); - - return tmp; -} - -template -inline Vector operator^(const T& a, const Vector& rhs) -{ - Vector tmp(rhs.size()); - for (unsigned int i = 0; i < rhs.size(); i++) - tmp[i] = pow(a, rhs[i]); - - return tmp; -} - -template -inline Vector& Vector::operator^=(const Vector& rhs) -{ - if (this->size() != rhs.size()) - throw std::logic_error("Operator^=: vectors have different sizes"); - for (unsigned int i = 0; i < n; i++) - v[i] = pow(v[i], rhs[i]); - - return *this; -} - -template -inline Vector& Vector::operator^=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - v[i] = pow(v[i], a); - - return *this; -} - -template -inline bool operator==(const Vector& v, const Vector& w) -{ - if (v.size() != w.size()) - throw std::logic_error("Vectors of different size are not confrontable"); - for (unsigned i = 0; i < v.size(); i++) - if (v[i] != w[i]) - return false; - return true; -} - -template -inline bool operator!=(const Vector& v, const Vector& w) -{ - if (v.size() != w.size()) - throw std::logic_error("Vectors of different size are not confrontable"); - for (unsigned i = 0; i < v.size(); i++) - if (v[i] != w[i]) - return true; - return false; -} - -template -inline bool operator<(const Vector& v, const Vector& w) -{ - if (v.size() != w.size()) - throw std::logic_error("Vectors of different size are not confrontable"); - for (unsigned i = 0; i < v.size(); i++) - if (v[i] >= w[i]) - return false; - return true; -} - -template -inline bool operator<=(const Vector& v, const Vector& w) -{ - if (v.size() != w.size()) - throw std::logic_error("Vectors of different size are not confrontable"); - for (unsigned i = 0; i < v.size(); i++) - if (v[i] > w[i]) - return false; - return true; -} - -template -inline bool operator>(const Vector& v, const Vector& w) -{ - if (v.size() != w.size()) - throw std::logic_error("Vectors of different size are not confrontable"); - for (unsigned i = 0; i < v.size(); i++) - if (v[i] <= w[i]) - return false; - return true; -} - -template -inline bool operator>=(const Vector& v, const Vector& w) -{ - if (v.size() != w.size()) - throw std::logic_error("Vectors of different size are not confrontable"); - for (unsigned i = 0; i < v.size(); i++) - if (v[i] < w[i]) - return false; - return true; -} - -/** - Input/Output -*/ -template -inline std::ostream& operator<<(std::ostream& os, const Vector& v) -{ - os << std::endl << v.size() << std::endl; - for (unsigned int i = 0; i < v.size() - 1; i++) - os << std::setw(20) << std::setprecision(16) << v[i] << ", "; - os << std::setw(20) << std::setprecision(16) << v[v.size() - 1] << std::endl; - - return os; -} - -template -std::istream& operator>>(std::istream& is, Vector& v) -{ - int elements; - char comma; - is >> elements; - v.resize(elements); - for (unsigned int i = 0; i < elements; i++) - is >> v[i] >> comma; - - return is; -} - -/** - Index utilities -*/ - -std::set seq(unsigned int s, unsigned int e); - -std::set singleton(unsigned int i); - -template -class CanonicalBaseVector : public Vector -{ -public: - CanonicalBaseVector(unsigned int i, unsigned int n); - inline void reset(unsigned int i); -private: - unsigned int e; -}; - -template -CanonicalBaseVector::CanonicalBaseVector(unsigned int i, unsigned int n) - : Vector((T)0, n), e(i) -{ (*this)[e] = (T)1; } - -template -inline void CanonicalBaseVector::reset(unsigned int i) -{ - (*this)[e] = (T)0; - e = i; - (*this)[e] = (T)1; -} - -#include - -template -inline T sum(const Vector& v) -{ - T tmp = (T)0; - for (unsigned int i = 0; i < v.size(); i++) - tmp += v[i]; - - return tmp; -} - -template -inline T prod(const Vector& v) -{ - T tmp = (T)1; - for (unsigned int i = 0; i < v.size(); i++) - tmp *= v[i]; - - return tmp; -} - -template -inline T mean(const Vector& v) -{ - T sum = (T)0; - for (unsigned int i = 0; i < v.size(); i++) - sum += v[i]; - return sum / v.size(); -} - -template -inline T median(const Vector& v) -{ - Vector tmp = sort(v); - if (v.size() % 2 == 1) // it is an odd-sized vector - return tmp[v.size() / 2]; - else - return 0.5 * (tmp[v.size() / 2 - 1] + tmp[v.size() / 2]); -} - -template -inline T stdev(const Vector& v, bool sample_correction = false) -{ - return sqrt(var(v, sample_correction)); -} - -template -inline T var(const Vector& v, bool sample_correction = false) -{ - T sum = (T)0, ssum = (T)0; - unsigned int n = v.size(); - for (unsigned int i = 0; i < n; i++) - { - sum += v[i]; - ssum += (v[i] * v[i]); - } - if (!sample_correction) - return (ssum / n) - (sum / n) * (sum / n); - else - return n * ((ssum / n) - (sum / n) * (sum / n)) / (n - 1); -} - -template -inline T max(const Vector& v) -{ - T value = v[0]; - for (unsigned int i = 1; i < v.size(); i++) - value = std::max(v[i], value); - - return value; -} - -template -inline T min(const Vector& v) -{ - T value = v[0]; - for (unsigned int i = 1; i < v.size(); i++) - value = std::min(v[i], value); - - return value; -} - -template -inline unsigned int index_max(const Vector& v) -{ - unsigned int max = 0; - for (unsigned int i = 1; i < v.size(); i++) - if (v[i] > v[max]) - max = i; - - return max; -} - -template -inline unsigned int index_min(const Vector& v) -{ - unsigned int min = 0; - for (unsigned int i = 1; i < v.size(); i++) - if (v[i] < v[min]) - min = i; - - return min; -} - - -template -inline T dot_prod(const Vector& a, const Vector& b) -{ - T sum = (T)0; - if (a.size() != b.size()) - throw std::logic_error("Dotprod error: the vectors are not the same size"); - for (unsigned int i = 0; i < a.size(); i++) - sum += a[i] * b[i]; - - return sum; -} - -/** - Single element mathematical functions -*/ - -template -inline Vector exp(const Vector& v) -{ - Vector tmp(v.size()); - for (unsigned int i = 0; i < v.size(); i++) - tmp[i] = exp(v[i]); - - return tmp; -} - -template -inline Vector log(const Vector& v) -{ - Vector tmp(v.size()); - for (unsigned int i = 0; i < v.size(); i++) - tmp[i] = log(v[i]); - - return tmp; -} - -template -inline Vector vec_sqrt(const Vector& v) -{ - Vector tmp(v.size()); - for (unsigned int i = 0; i < v.size(); i++) - tmp[i] = sqrt(v[i]); - - return tmp; -} - -template -inline Vector pow(const Vector& v, double a) -{ - Vector tmp(v.size()); - for (unsigned int i = 0; i < v.size(); i++) - tmp[i] = pow(v[i], a); - - return tmp; -} - -template -inline Vector abs(const Vector& v) -{ - Vector tmp(v.size()); - for (unsigned int i = 0; i < v.size(); i++) - tmp[i] = (T)fabs(v[i]); - - return tmp; -} - -template -inline Vector sign(const Vector& v) -{ - Vector tmp(v.size()); - for (unsigned int i = 0; i < v.size(); i++) - tmp[i] = v[i] > 0 ? +1 : v[i] == 0 ? 0 : -1; - - return tmp; -} - -template -inline unsigned int partition(Vector& v, unsigned int begin, unsigned int end) -{ - unsigned int i = begin + 1, j = begin + 1; - T pivot = v[begin]; - while (j <= end) - { - if (v[j] < pivot) { - std::swap(v[i], v[j]); - i++; - } - j++; - } - v[begin] = v[i - 1]; - v[i - 1] = pivot; - return i - 2; -} - - -template -inline void quicksort(Vector& v, unsigned int begin, unsigned int end) -{ - if (end > begin) - { - unsigned int index = partition(v, begin, end); - quicksort(v, begin, index); - quicksort(v, index + 2, end); - } -} - -template -inline Vector sort(const Vector& v) -{ - Vector tmp(v); - - quicksort(tmp, 0, tmp.size() - 1); - - return tmp; -} - -template -inline Vector rank(const Vector& v) -{ - Vector tmp(v); - Vector tmp_rank(0.0, v.size()); - - for (unsigned int i = 0; i < tmp.size(); i++) - { - unsigned int smaller = 0, equal = 0; - for (unsigned int j = 0; j < tmp.size(); j++) - if (i == j) - continue; - else - if (tmp[j] < tmp[i]) - smaller++; - else if (tmp[j] == tmp[i]) - equal++; - tmp_rank[i] = smaller + 1; - if (equal > 0) - { - for (unsigned int j = 1; j <= equal; j++) - tmp_rank[i] += smaller + 1 + j; - tmp_rank[i] /= (double)(equal + 1); - } - } - - return tmp_rank; -} - -//enum MType { DIAG }; - -template -class Matrix -{ -public: - Matrix(); // Default constructor - Matrix(const unsigned int n, const unsigned int m); // Construct a n x m matrix - Matrix(const T& a, const unsigned int n, const unsigned int m); // Initialize the content to constant a - Matrix(MType t, const T& a, const T& o, const unsigned int n, const unsigned int m); - Matrix(MType t, const Vector& v, const T& o, const unsigned int n, const unsigned int m); - Matrix(const T* a, const unsigned int n, const unsigned int m); // Initialize to array - Matrix(const Matrix& rhs); // Copy constructor - ~Matrix(); // destructor - - inline T* operator[](const unsigned int& i) { return v[i]; } // Subscripting: row i - inline const T* operator[](const unsigned int& i) const { return v[i]; }; // const subsctipting - - inline void resize(const unsigned int n, const unsigned int m); - inline void resize(const T& a, const unsigned int n, const unsigned int m); - - - inline Vector extractRow(const unsigned int i) const; - inline Vector extractColumn(const unsigned int j) const; - inline Vector extractDiag() const; - inline Matrix extractRows(const std::set& indexes) const; - inline Matrix extractColumns(const std::set& indexes) const; - inline Matrix extract(const std::set& r_indexes, const std::set& c_indexes) const; - - inline void set(const T* a, unsigned int n, unsigned int m); - inline void set(const std::set& r_indexes, const std::set& c_indexes, const Matrix& m); - inline void setRow(const unsigned int index, const Vector& v); - inline void setRow(const unsigned int index, const Matrix& v); - inline void setRows(const std::set& indexes, const Matrix& m); - inline void setColumn(const unsigned int index, const Vector& v); - inline void setColumn(const unsigned int index, const Matrix& v); - inline void setColumns(const std::set& indexes, const Matrix& m); - - - inline unsigned int nrows() const { return n; } // number of rows - inline unsigned int ncols() const { return m; } // number of columns - - inline Matrix& operator=(const Matrix& rhs); // Assignment operator - inline Matrix& operator=(const T& a); // Assign to every element value a - inline Matrix& operator+=(const Matrix& rhs); - inline Matrix& operator-=(const Matrix& rhs); - inline Matrix& operator*=(const Matrix& rhs); - inline Matrix& operator/=(const Matrix& rhs); - inline Matrix& operator^=(const Matrix& rhs); - inline Matrix& operator+=(const T& a); - inline Matrix& operator-=(const T& a); - inline Matrix& operator*=(const T& a); - inline Matrix& operator/=(const T& a); - inline Matrix& operator^=(const T& a); - inline operator Vector(); -private: - unsigned int n; // number of rows - unsigned int m; // number of columns - T **v; // storage for data -}; - -template -Matrix::Matrix() - : n(0), m(0), v(0) -{} - -template -Matrix::Matrix(unsigned int n, unsigned int m) - : v(new T*[n]) -{ - this->n = n; this->m = m; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; -} - -template -Matrix::Matrix(const T& a, unsigned int n, unsigned int m) - : v(new T*[n]) -{ - this->n = n; this->m = m; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = a; -} - -template -Matrix::Matrix(const T* a, unsigned int n, unsigned int m) - : v(new T*[n]) -{ - this->n = n; this->m = m; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = *a++; -} - -template -Matrix::Matrix(MType t, const T& a, const T& o, unsigned int n, unsigned int m) - : v(new T*[n]) -{ - this->n = n; this->m = m; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; - switch (t) - { - case DIAG: - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - if (i != j) - v[i][j] = o; - else - v[i][j] = a; - break; - default: - throw std::logic_error("Matrix type not supported"); - } -} - -template -Matrix::Matrix(MType t, const Vector& a, const T& o, unsigned int n, unsigned int m) - : v(new T*[n]) -{ - this->n = n; this->m = m; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; - switch (t) - { - case DIAG: - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - if (i != j) - v[i][j] = o; - else - v[i][j] = a[i]; - break; - default: - throw std::logic_error("Matrix type not supported"); - } -} - -template -Matrix::Matrix(const Matrix& rhs) - : v(new T*[rhs.n]) -{ - n = rhs.n; m = rhs.m; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = rhs[i][j]; -} - -template -Matrix::~Matrix() -{ - if (v != 0) { - delete[] (v[0]); - delete[] (v); - } -} - -template -inline Matrix& Matrix::operator=(const Matrix &rhs) -// postcondition: normal assignment via copying has been performed; -// if matrix and rhs were different sizes, matrix -// has been resized to match the size of rhs -{ - if (this != &rhs) - { - resize(rhs.n, rhs.m); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = rhs[i][j]; - } - return *this; -} - -template -inline Matrix& Matrix::operator=(const T& a) // assign a to every element -{ - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = a; - return *this; -} - - -template -inline void Matrix::resize(const unsigned int n, const unsigned int m) -{ - if (n == this->n && m == this->m) - return; - if (v != 0) - { - delete[] (v[0]); - delete[] (v); - } - this->n = n; this->m = m; - v = new T*[n]; - v[0] = new T[m * n]; - for (unsigned int i = 1; i < n; i++) - v[i] = v[i - 1] + m; -} - -template -inline void Matrix::resize(const T& a, const unsigned int n, const unsigned int m) -{ - resize(n, m); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = a; -} - - - -template -inline Vector Matrix::extractRow(const unsigned int i) const -{ - if (i >= n) - throw std::logic_error("Error in extractRow: trying to extract a row out of matrix bounds"); - Vector tmp(v[i], m); - - return tmp; -} - -template -inline Vector Matrix::extractColumn(const unsigned int j) const -{ - if (j >= m) - throw std::logic_error("Error in extractRow: trying to extract a row out of matrix bounds"); - Vector tmp(n); - - for (unsigned int i = 0; i < n; i++) - tmp[i] = v[i][j]; - - return tmp; -} - -template -inline Vector Matrix::extractDiag() const -{ - unsigned int d = std::min(n, m); - - Vector tmp(d); - - for (unsigned int i = 0; i < d; i++) - tmp[i] = v[i][i]; - - return tmp; - -} - -template -inline Matrix Matrix::extractRows(const std::set& indexes) const -{ - Matrix tmp(indexes.size(), m); - unsigned int i = 0; - - for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) - { - for (unsigned int j = 0; j < m; j++) - { - if (*el >= n) - throw std::logic_error("Error extracting rows: the indexes are out of matrix bounds"); - tmp[i][j] = v[*el][j]; - } - i++; - } - - return tmp; -} - -template -inline Matrix Matrix::extractColumns(const std::set& indexes) const -{ - Matrix tmp(n, indexes.size()); - unsigned int j = 0; - - for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) - { - for (unsigned int i = 0; i < n; i++) - { - if (*el >= m) - throw std::logic_error("Error extracting columns: the indexes are out of matrix bounds"); - tmp[i][j] = v[i][*el]; - } - j++; - } - - return tmp; -} - -template -inline Matrix Matrix::extract(const std::set& r_indexes, const std::set& c_indexes) const -{ - Matrix tmp(r_indexes.size(), c_indexes.size()); - unsigned int i = 0, j; - - for (std::set::const_iterator r_el = r_indexes.begin(); r_el != r_indexes.end(); r_el++) - { - if (*r_el >= n) - throw std::logic_error("Error extracting submatrix: the indexes are out of matrix bounds"); - j = 0; - for (std::set::const_iterator c_el = c_indexes.begin(); c_el != c_indexes.end(); c_el++) - { - if (*c_el >= m) - throw std::logic_error("Error extracting rows: the indexes are out of matrix bounds"); - tmp[i][j] = v[*r_el][*c_el]; - j++; - } - i++; - } - - return tmp; -} - -template -inline void Matrix::setRow(unsigned int i, const Vector& a) -{ - if (i >= n) - throw std::logic_error("Error in setRow: trying to set a row out of matrix bounds"); - if (this->m != a.size()) - throw std::logic_error("Error setting matrix row: ranges are not compatible"); - for (unsigned int j = 0; j < ncols(); j++) - v[i][j] = a[j]; -} - -template -inline void Matrix::setRow(unsigned int i, const Matrix& a) -{ - if (i >= n) - throw std::logic_error("Error in setRow: trying to set a row out of matrix bounds"); - if (this->m != a.ncols()) - throw std::logic_error("Error setting matrix column: ranges are not compatible"); - if (a.nrows() != 1) - throw std::logic_error("Error setting matrix column with a non-row matrix"); - for (unsigned int j = 0; j < ncols(); j++) - v[i][j] = a[0][j]; -} - -template -inline void Matrix::setRows(const std::set& indexes, const Matrix& m) -{ - unsigned int i = 0; - - if (indexes.size() != m.nrows() || this->m != m.ncols()) - throw std::logic_error("Error setting matrix rows: ranges are not compatible"); - for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) - { - for (unsigned int j = 0; j < ncols(); j++) - { - if (*el >= n) - throw std::logic_error("Error in setRows: trying to set a row out of matrix bounds"); - v[*el][j] = m[i][j]; - } - i++; - } -} - -template -inline void Matrix::setColumn(unsigned int j, const Vector& a) -{ - if (j >= m) - throw std::logic_error("Error in setColumn: trying to set a column out of matrix bounds"); - if (this->n != a.size()) - throw std::logic_error("Error setting matrix column: ranges are not compatible"); - for (unsigned int i = 0; i < nrows(); i++) - v[i][j] = a[i]; -} - -template -inline void Matrix::setColumn(unsigned int j, const Matrix& a) -{ - if (j >= m) - throw std::logic_error("Error in setColumn: trying to set a column out of matrix bounds"); - if (this->n != a.nrows()) - throw std::logic_error("Error setting matrix column: ranges are not compatible"); - if (a.ncols() != 1) - throw std::logic_error("Error setting matrix column with a non-column matrix"); - for (unsigned int i = 0; i < nrows(); i++) - v[i][j] = a[i][0]; -} - - -template -inline void Matrix::setColumns(const std::set& indexes, const Matrix& a) -{ - unsigned int j = 0; - - if (indexes.size() != a.ncols() || this->n != a.nrows()) - throw std::logic_error("Error setting matrix columns: ranges are not compatible"); - for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) - { - for (unsigned int i = 0; i < nrows(); i++) - { - if (*el >= m) - throw std::logic_error("Error in setColumns: trying to set a column out of matrix bounds"); - v[i][*el] = a[i][j]; - } - j++; - } -} - -template -inline void Matrix::set(const std::set& r_indexes, const std::set& c_indexes, const Matrix& a) -{ - unsigned int i = 0, j; - if (c_indexes.size() != a.ncols() || r_indexes.size() != a.nrows()) - throw std::logic_error("Error setting matrix elements: ranges are not compatible"); - - for (std::set::const_iterator r_el = r_indexes.begin(); r_el != r_indexes.end(); r_el++) - { - if (*r_el >= n) - throw std::logic_error("Error in set: trying to set a row out of matrix bounds"); - j = 0; - for (std::set::const_iterator c_el = c_indexes.begin(); c_el != c_indexes.end(); c_el++) - { - if (*c_el >= m) - throw std::logic_error("Error in set: trying to set a column out of matrix bounds"); - v[*r_el][*c_el] = a[i][j]; - j++; - } - i++; - } -} - -template -inline void Matrix::set(const T* a, unsigned int n, unsigned int m) -{ - if (this->n != n || this->m != m) - resize(n, m); - unsigned int k = 0; - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = a[k++]; -} - - -template -Matrix operator+(const Matrix& rhs) -{ - return rhs; -} - -template -Matrix operator+(const Matrix& lhs, const Matrix& rhs) -{ - if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) - throw std::logic_error("Operator+: matrices have different sizes"); - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] + rhs[i][j]; - - return tmp; -} - -template -Matrix operator+(const Matrix& lhs, const T& a) -{ - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] + a; - - return tmp; -} - -template -Matrix operator+(const T& a, const Matrix& rhs) -{ - Matrix tmp(rhs.nrows(), rhs.ncols()); - for (unsigned int i = 0; i < rhs.nrows(); i++) - for (unsigned int j = 0; j < rhs.ncols(); j++) - tmp[i][j] = a + rhs[i][j]; - - return tmp; -} - -template -inline Matrix& Matrix::operator+=(const Matrix& rhs) -{ - if (m != rhs.ncols() || n != rhs.nrows()) - throw std::logic_error("Operator+=: matrices have different sizes"); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] += rhs[i][j]; - - return *this; -} - -template -inline Matrix& Matrix::operator+=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] += a; - - return *this; -} - -template -Matrix operator-(const Matrix& rhs) -{ - return (T)(-1) * rhs; -} - -template -Matrix operator-(const Matrix& lhs, const Matrix& rhs) -{ - if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) - throw std::logic_error("Operator-: matrices have different sizes"); - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] - rhs[i][j]; - - return tmp; -} - -template -Matrix operator-(const Matrix& lhs, const T& a) -{ - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] - a; - - return tmp; -} - -template -Matrix operator-(const T& a, const Matrix& rhs) -{ - Matrix tmp(rhs.nrows(), rhs.ncols()); - for (unsigned int i = 0; i < rhs.nrows(); i++) - for (unsigned int j = 0; j < rhs.ncols(); j++) - tmp[i][j] = a - rhs[i][j]; - - return tmp; -} - -template -inline Matrix& Matrix::operator-=(const Matrix& rhs) -{ - if (m != rhs.ncols() || n != rhs.nrows()) - throw std::logic_error("Operator-=: matrices have different sizes"); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] -= rhs[i][j]; - - return *this; -} - -template -inline Matrix& Matrix::operator-=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] -= a; - - return *this; -} - -template -Matrix operator*(const Matrix& lhs, const Matrix& rhs) -{ - if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) - throw std::logic_error("Operator*: matrices have different sizes"); - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] * rhs[i][j]; - - return tmp; -} - -template -Matrix operator*(const Matrix& lhs, const T& a) -{ - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] * a; - - return tmp; -} - -template -Matrix operator*(const T& a, const Matrix& rhs) -{ - Matrix tmp(rhs.nrows(), rhs.ncols()); - for (unsigned int i = 0; i < rhs.nrows(); i++) - for (unsigned int j = 0; j < rhs.ncols(); j++) - tmp[i][j] = a * rhs[i][j]; - - return tmp; -} - -template -inline Matrix& Matrix::operator*=(const Matrix& rhs) -{ - if (m != rhs.ncols() || n != rhs.nrows()) - throw std::logic_error("Operator*=: matrices have different sizes"); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] *= rhs[i][j]; - - return *this; -} - -template -inline Matrix& Matrix::operator*=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] *= a; - - return *this; -} - -template -Matrix operator/(const Matrix& lhs, const Matrix& rhs) -{ - if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) - throw std::logic_error("Operator+: matrices have different sizes"); - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] / rhs[i][j]; - - return tmp; -} - -template -Matrix operator/(const Matrix& lhs, const T& a) -{ - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = lhs[i][j] / a; - - return tmp; -} - -template -Matrix operator/(const T& a, const Matrix& rhs) -{ - Matrix tmp(rhs.nrows(), rhs.ncols()); - for (unsigned int i = 0; i < rhs.nrows(); i++) - for (unsigned int j = 0; j < rhs.ncols(); j++) - tmp[i][j] = a / rhs[i][j]; - - return tmp; -} - -template -inline Matrix& Matrix::operator/=(const Matrix& rhs) -{ - if (m != rhs.ncols() || n != rhs.nrows()) - throw std::logic_error("Operator+=: matrices have different sizes"); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] /= rhs[i][j]; - - return *this; -} - -template -inline Matrix& Matrix::operator/=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] /= a; - - return *this; -} - -template -Matrix operator^(const Matrix& lhs, const T& a) -{ - Matrix tmp(lhs.nrows(), lhs.ncols()); - for (unsigned int i = 0; i < lhs.nrows(); i++) - for (unsigned int j = 0; j < lhs.ncols(); j++) - tmp[i][j] = pow(lhs[i][j], a); - - return tmp; -} - -template -inline Matrix& Matrix::operator^=(const Matrix& rhs) -{ - if (m != rhs.ncols() || n != rhs.nrows()) - throw std::logic_error("Operator^=: matrices have different sizes"); - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = pow(v[i][j], rhs[i][j]); - - return *this; -} - - -template -inline Matrix& Matrix::operator^=(const T& a) -{ - for (unsigned int i = 0; i < n; i++) - for (unsigned int j = 0; j < m; j++) - v[i][j] = pow(v[i][j], a); - - return *this; -} - -template -inline Matrix::operator Vector() -{ - if (n > 1 && m > 1) - throw std::logic_error("Error matrix cast to vector: trying to cast a multi-dimensional matrix"); - if (n == 1) - return extractRow(0); - else - return extractColumn(0); -} - -template -inline bool operator==(const Matrix& a, const Matrix& b) -{ - if (a.nrows() != b.nrows() || a.ncols() != b.ncols()) - throw std::logic_error("Matrices of different size are not confrontable"); - for (unsigned i = 0; i < a.nrows(); i++) - for (unsigned j = 0; j < a.ncols(); j++) - if (a[i][j] != b[i][j]) - return false; - return true; -} - -template -inline bool operator!=(const Matrix& a, const Matrix& b) -{ - if (a.nrows() != b.nrows() || a.ncols() != b.ncols()) - throw std::logic_error("Matrices of different size are not confrontable"); - for (unsigned i = 0; i < a.nrows(); i++) - for (unsigned j = 0; j < a.ncols(); j++) - if (a[i][j] != b[i][j]) - return true; - return false; -} - - - -/** - Input/Output -*/ -template -std::ostream& operator<<(std::ostream& os, const Matrix& m) -{ - os << std::endl << m.nrows() << " " << m.ncols() << std::endl; - for (unsigned int i = 0; i < m.nrows(); i++) - { - for (unsigned int j = 0; j < m.ncols() - 1; j++) - os << std::setw(20) << std::setprecision(16) << m[i][j] << ", "; - os << std::setw(20) << std::setprecision(16) << m[i][m.ncols() - 1] << std::endl; - } - - return os; -} - -template -std::istream& operator>>(std::istream& is, Matrix& m) -{ - int rows, cols; - char comma; - is >> rows >> cols; - m.resize(rows, cols); - for (unsigned int i = 0; i < rows; i++) - for (unsigned int j = 0; j < cols; j++) - is >> m[i][j] >> comma; - - return is; -} - -template -T sign(const T& v) -{ - if (v >= (T)0.0) - return (T)1.0; - else - return (T)-1.0; -} - -template -T dist(const T& a, const T& b) -{ - T abs_a = (T)fabs(a), abs_b = (T)fabs(b); - if (abs_a > abs_b) - return abs_a * sqrt((T)1.0 + (abs_b / abs_a) * (abs_b / abs_a)); - else - return (abs_b == (T)0.0 ? (T)0.0 : abs_b * sqrt((T)1.0 + (abs_a / abs_b) * (abs_a / abs_b))); -} - -template -void svd(const Matrix& A, Matrix& U, Vector& W, Matrix& V) -{ - int m = A.nrows(), n = A.ncols(), i, j, k, l, jj, nm; - const unsigned int max_its = 30; - bool flag; - Vector rv1(n); - U = A; - W.resize(n); - V.resize(n, n); - T anorm, c, f, g, h, s, scale, x, y, z; - g = scale = anorm = (T)0.0; - - // Householder reduction to bidiagonal form - for (i = 0; i < n; i++) - { - l = i + 1; - rv1[i] = scale * g; - g = s = scale = (T)0.0; - if (i < m) - { - for (k = i; k < m; k++) - scale += fabs(U[k][i]); - if (scale != (T)0.0) - { - for (k = i; k < m; k++) - { - U[k][i] /= scale; - s += U[k][i] * U[k][i]; - } - f = U[i][i]; - g = -sign(f) * sqrt(s); - h = f * g - s; - U[i][i] = f - g; - for (j = l; j < n; j++) - { - s = (T)0.0; - for (k = i; k < m; k++) - s += U[k][i] * U[k][j]; - f = s / h; - for (k = i; k < m; k++) - U[k][j] += f * U[k][i]; - } - for (k = i; k < m; k++) - U[k][i] *= scale; - } - } - W[i] = scale * g; - g = s = scale = (T)0.0; - if (i < m && i != n - 1) - { - for (k = l; k < n; k++) - scale += fabs(U[i][k]); - if (scale != (T)0.0) - { - for (k = l; k < n; k++) - { - U[i][k] /= scale; - s += U[i][k] * U[i][k]; - } - f = U[i][l]; - g = -sign(f) * sqrt(s); - h = f * g - s; - U[i][l] = f - g; - for (k = l; k = 0; i--) - { - if (i < n - 1) - { - if (g != (T)0.0) - { - for (j = l; j < n; j++) - V[j][i] = (U[i][j] / U[i][l]) / g; - for (j = l; j < n; j++) - { - s = (T)0.0; - for (k = l; k < n; k++) - s += U[i][k] * V[k][j]; - for (k = l; k < n; k++) - V[k][j] += s * V[k][i]; - } - } - for (j = l; j < n; j++) - V[i][j] = V[j][i] = (T)0.0; - } - V[i][i] = (T)1.0; - g = rv1[i]; - l = i; - } - // Accumulation of left-hand transformations - for (i = std::min(m, n) - 1; i >= 0; i--) - { - l = i + 1; - g = W[i]; - for (j = l; j < n; j++) - U[i][j] = (T)0.0; - if (g != (T)0.0) - { - g = (T)1.0 / g; - for (j = l; j < n; j++) - { - s = (T)0.0; - for (k = l; k < m; k++) - s += U[k][i] * U[k][j]; - f = (s / U[i][i]) * g; - for (k = i; k < m; k++) - U[k][j] += f * U[k][i]; - } - for (j = i; j < m; j++) - U[j][i] *= g; - } - else - for (j = i; j < m; j++) - U[j][i] = (T)0.0; - U[i][i]++; - } - // Diagonalization of the bidiagonal form: loop over singular values, and over allowed iterations. - for (k = n - 1; k >= 0; k--) - { - for (unsigned int its = 0; its < max_its; its++) - { - flag = true; - for (l = k; l >= 0; l--) - { // Test for splitting - nm = l - 1; // Note that rV[0] is always zero - if ((T)(fabs(rv1[l]) + anorm) == anorm) - { - flag = false; - break; - } - if ((T)(fabs(W[nm]) + anorm) == anorm) - break; - } - if (flag) - { - // Cancellation of rv1[l], if l > 0 FIXME: it was l > 1 in NR - c = (T)0.0; - s = (T)1.0; - for (i = l; i <= k; i++) - { - f = s * rv1[i]; - rv1[i] *= c; - if ((T)(fabs(f) + anorm) == anorm) - break; - g = W[i]; - h = dist(f, g); - W[i] = h; - h = (T)1.0 / h; - c = g * h; - s = -f * h; - for (j = 0; j < m; j++) - { - y = U[j][nm]; - z = U[j][i]; - U[j][nm] = y * c + z * s; - U[j][i] = z * c - y * s; - } - } - } - z = W[k]; - if (l == k) - { // Convergence - if (z < (T)0.0) - { // Singular value is made nonnegative - W[k] = -z; - for (j = 0; j < n; j++) - V[j][k] = -V[j][k]; - } - break; - } - if (its == max_its) - throw std::logic_error("Error svd: no convergence in the maximum number of iterations"); - x = W[l]; - nm = k - 1; - y = W[nm]; - g = rv1[nm]; - h = rv1[k]; - f = ((y - z) * (y + z) + (g - h) * (g + h)) / (2.0 * h * y); - g = dist(f, (T)1.0); - f = ((x - z) * (x + z) + h * ((y / (f + sign(f)*fabs(g))) - h)) / x; - c = s = (T)1.0; // Next QR transformation - for (j = l; j <= nm; j++) - { - i = j + 1; - g = rv1[i]; - y = W[i]; - h = s * g; - g *= c; - z = dist(f, h); - rv1[j] = z; - c = f / z; - s = h / z; - f = x * c + g * s; - g = g * c - x * s; - h = y * s; - y *= c; - for (jj = 0; jj < n; jj++) - { - x = V[jj][j]; - z = V[jj][i]; - V[jj][j] = x * c + z * s; - V[jj][i] = z * c - x * s; - } - z = dist(f, h); - W[j] = z; - if (z != 0) // Rotation can be arbitrary if z = 0 - { - z = (T)1.0 / z; - c = f * z; - s = h * z; - } - f = c * g + s * y; - x = c * y - s * g; - for (jj = 0; jj < m; jj++) - { - y = U[jj][j]; - z = U[jj][i]; - U[jj][j] = y * c + z * s; - U[jj][i] = z * c - y * s; - } - } - rv1[l] = (T)0.0; - rv1[k] = f; - W[k] = x; - } - } -} - -template -Matrix pinv(const Matrix& A) -{ - Matrix U, V, x, tmp(A.ncols(), A.nrows()); - Vector W; - CanonicalBaseVector e(0, A.nrows()); - svd(A, U, W, V); - for (unsigned int i = 0; i < A.nrows(); i++) - { - e.reset(i); - tmp.setColumn(i, dot_prod(dot_prod(dot_prod(V, Matrix(DIAG, 1.0 / W, 0.0, W.size(), W.size())), t(U)), e)); - } - - return tmp; -} - -template -int lu(const Matrix& A, Matrix& LU, Vector& index) -{ - if (A.ncols() != A.nrows()) - throw std::logic_error("Error in LU decomposition: matrix must be squared"); - int i, p, j, k, n = A.ncols(), ex; - T val, tmp; - Vector d(n); - LU = A; - index.resize(n); - - ex = 1; - for (i = 0; i < n; i++) - { - index[i] = i; - val = (T)0.0; - for (j = 0; j < n; j++) - val = std::max(val, (T)fabs(LU[i][j])); - if (val == (T)0.0) - std::logic_error("Error in LU decomposition: matrix was singular"); - d[i] = val; - } - - for (k = 0; k < n - 1; k++) - { - p = k; - val = fabs(LU[k][k]) / d[k]; - for (i = k + 1; i < n; i++) - { - tmp = fabs(LU[i][k]) / d[i]; - if (tmp > val) - { - val = tmp; - p = i; - } - } - if (val == (T)0.0) - std::logic_error("Error in LU decomposition: matrix was singular"); - if (p > k) - { - ex = -ex; - std::swap(index[k], index[p]); - std::swap(d[k], d[p]); - for (j = 0; j < n; j++) - std::swap(LU[k][j], LU[p][j]); - } - - for (i = k + 1; i < n; i++) - { - LU[i][k] /= LU[k][k]; - for (j = k + 1; j < n; j++) - LU[i][j] -= LU[i][k] * LU[k][j]; - } - } - if (LU[n - 1][n - 1] == (T)0.0) - std::logic_error("Error in LU decomposition: matrix was singular"); - - return ex; -} - -template -Vector lu_solve(const Matrix& LU, const Vector& b, Vector& index) -{ - if (LU.ncols() != LU.nrows()) - throw std::logic_error("Error in LU solve: LU matrix should be squared"); - unsigned int n = LU.ncols(); - if (b.size() != n) - throw std::logic_error("Error in LU solve: b vector must be of the same dimensions of LU matrix"); - Vector x((T)0.0, n); - int i, j, p; - T sum; - - p = index[0]; - x[0] = b[p]; - - for (i = 1; i < n; i++) - { - sum = (T)0.0; - for (j = 0; j < i; j++) - sum += LU[i][j] * x[j]; - p = index[i]; - x[i] = b[p] - sum; - } - x[n - 1] /= LU[n - 1][n - 1]; - for (i = n - 2; i >= 0; i--) - { - sum = (T)0.0; - for (j = i + 1; j < n; j++) - sum += LU[i][j] * x[j]; - x[i] = (x[i] - sum) / LU[i][i]; - } - return x; -} - -template -void lu_solve(const Matrix& LU, Vector& x, const Vector& b, Vector& index) -{ - x = lu_solve(LU, b, index); -} - -template -Matrix lu_inverse(const Matrix& A) -{ - if (A.ncols() != A.nrows()) - throw std::logic_error("Error in LU invert: matrix must be squared"); - unsigned int n = A.ncols(); - Matrix A1(n, n), LU; - Vector index; - - lu(A, LU, index); - CanonicalBaseVector e(0, n); - for (unsigned i = 0; i < n; i++) - { - e.reset(i); - A1.setColumn(i, lu_solve(LU, e, index)); - } - - return A1; -} - -template -T lu_det(const Matrix& A) -{ - if (A.ncols() != A.nrows()) - throw std::logic_error("Error in LU determinant: matrix must be squared"); - unsigned int d; - Matrix LU; - Vector index; - - d = lu(A, LU, index); - - return d * prod(LU.extractDiag()); -} - -template -void cholesky(const Matrix A, Matrix& LL) -{ - if (A.ncols() != A.nrows()) - throw std::logic_error("Error in Cholesky decomposition: matrix must be squared"); - int n = A.ncols(); - double sum; - LL = A; - - for (unsigned int i = 0; i < n; i++) - { - for (unsigned int j = i; j < n; j++) - { - sum = LL[i][j]; - for (int k = i - 1; k >= 0; k--) - sum -= LL[i][k] * LL[j][k]; - if (i == j) - { - if (sum <= 0.0) - throw std::logic_error("Error in Cholesky decomposition: matrix is not postive definite"); - LL[i][i] = sqrt(sum); - } - else - LL[j][i] = sum / LL[i][i]; - } - for (unsigned int k = i + 1; k < n; k++) - LL[i][k] = LL[k][i]; - } -} - -template -Matrix cholesky(const Matrix A) -{ - Matrix LL; - cholesky(A, LL); - - return LL; -} - -template -Vector cholesky_solve(const Matrix& LL, const Vector& b) -{ - if (LL.ncols() != LL.nrows()) - throw std::logic_error("Error in Cholesky solve: matrix must be squared"); - unsigned int n = LL.ncols(); - if (b.size() != n) - throw std::logic_error("Error in Cholesky decomposition: b vector must be of the same dimensions of LU matrix"); - Vector x, y; - - /* Solve L * y = b */ - forward_elimination(LL, y, b); - /* Solve L^T * x = y */ - backward_elimination(LL, x, y); - - return x; -} - -template -void cholesky_solve(const Matrix& LL, Vector& x, const Vector& b) -{ - x = cholesky_solve(LL, b); -} - -template -void forward_elimination(const Matrix& L, Vector& y, const Vector b) -{ - if (L.ncols() != L.nrows()) - throw std::logic_error("Error in Forward elimination: matrix must be squared (lower triangular)"); - if (b.size() != L.nrows()) - throw std::logic_error("Error in Forward elimination: b vector must be of the same dimensions of L matrix"); - unsigned int n = b.size(); - y.resize(n); - - y[0] = b[0] / L[0][0]; - for (unsigned int i = 1; i < n; i++) - { - y[i] = b[i]; - for (unsigned int j = 0; j < i; j++) - y[i] -= L[i][j] * y[j]; - y[i] = y[i] / L[i][i]; - } -} - -template -Vector forward_elimination(const Matrix& L, const Vector b) -{ - Vector y; - forward_elimination(L, y, b); - - return y; -} - -template -void backward_elimination(const Matrix& U, Vector& x, const Vector& y) -{ - if (U.ncols() != U.nrows()) - throw std::logic_error("Error in Backward elimination: matrix must be squared (upper triangular)"); - if (y.size() != U.nrows()) - throw std::logic_error("Error in Backward elimination: b vector must be of the same dimensions of U matrix"); - int n = y.size(); - x.resize(n); - - x[n - 1] = y[n - 1] / U[n - 1][n - 1]; - for (int i = n - 2; i >= 0; i--) - { - x[i] = y[i]; - for (int j = i + 1; j < n; j++) - x[i] -= U[i][j] * x[j]; - x[i] = x[i] / U[i][i]; - } -} - -template -Vector backward_elimination(const Matrix& U, const Vector y) -{ - Vector x; - forward_elimination(U, x, y); - - return x; -} - -/* Setting default linear systems machinery */ - -// #define det lu_det -// #define inverse lu_inverse -// #define solve lu_solve - -/* Random */ - -template -void random(Matrix& m) -{ - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - m[i][j] = (T)(rand() / double(RAND_MAX)); -} - -/** - Aggregate functions -*/ - -template -Vector sum(const Matrix& m) -{ - Vector tmp((T)0, m.ncols()); - for (unsigned int j = 0; j < m.ncols(); j++) - for (unsigned int i = 0; i < m.nrows(); i++) - tmp[j] += m[i][j]; - return tmp; -} - -template -Vector r_sum(const Matrix& m) -{ - Vector tmp((T)0, m.nrows()); - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp[i] += m[i][j]; - return tmp; -} - -template -T all_sum(const Matrix& m) -{ - T tmp = (T)0; - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp += m[i][j]; - return tmp; -} - -template -Vector prod(const Matrix& m) -{ - Vector tmp((T)1, m.ncols()); - for (unsigned int j = 0; j < m.ncols(); j++) - for (unsigned int i = 0; i < m.nrows(); i++) - tmp[j] *= m[i][j]; - return tmp; -} - -template -Vector r_prod(const Matrix& m) -{ - Vector tmp((T)1, m.nrows()); - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp[i] *= m[i][j]; - return tmp; -} - -template -T all_prod(const Matrix& m) -{ - T tmp = (T)1; - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp *= m[i][j]; - return tmp; -} - -template -Vector mean(const Matrix& m) -{ - Vector res((T)0, m.ncols()); - for (unsigned int j = 0; j < m.ncols(); j++) - { - for (unsigned int i = 0; i < m.nrows(); i++) - res[j] += m[i][j]; - res[j] /= m.nrows(); - } - - return res; -} - -template -Vector r_mean(const Matrix& m) -{ - Vector res((T)0, m.rows()); - for (unsigned int i = 0; i < m.nrows(); i++) - { - for (unsigned int j = 0; j < m.ncols(); j++) - res[i] += m[i][j]; - res[i] /= m.nrows(); - } - - return res; -} - -template -T all_mean(const Matrix& m) -{ - T tmp = (T)0; - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp += m[i][j]; - return tmp / (m.nrows() * m.ncols()); -} - -template -Vector var(const Matrix& m, bool sample_correction = false) -{ - Vector res((T)0, m.ncols()); - unsigned int n = m.nrows(); - double sum, ssum; - for (unsigned int j = 0; j < m.ncols(); j++) - { - sum = (T)0.0; ssum = (T)0.0; - for (unsigned int i = 0; i < m.nrows(); i++) - { - sum += m[i][j]; - ssum += (m[i][j] * m[i][j]); - } - if (!sample_correction) - res[j] = (ssum / n) - (sum / n) * (sum / n); - else - res[j] = n * ((ssum / n) - (sum / n) * (sum / n)) / (n - 1); - } - - return res; -} - -template -Vector stdev(const Matrix& m, bool sample_correction = false) -{ - return vec_sqrt(var(m, sample_correction)); -} - -template -Vector r_var(const Matrix& m, bool sample_correction = false) -{ - Vector res((T)0, m.nrows()); - double sum, ssum; - unsigned int n = m.ncols(); - for (unsigned int i = 0; i < m.nrows(); i++) - { - sum = 0.0; ssum = 0.0; - for (unsigned int j = 0; j < m.ncols(); j++) - { - sum += m[i][j]; - ssum += (m[i][j] * m[i][j]); - } - if (!sample_correction) - res[i] = (ssum / n) - (sum / n) * (sum / n); - else - res[i] = n * ((ssum / n) - (sum / n) * (sum / n)) / (n - 1); - } - - return res; -} - -template -Vector r_stdev(const Matrix& m, bool sample_correction = false) -{ - return vec_sqrt(r_var(m, sample_correction)); -} - -template -Vector max(const Matrix& m) -{ - Vector res(m.ncols()); - double value; - for (unsigned int j = 0; j < m.ncols(); j++) - { - value = m[0][j]; - for (unsigned int i = 1; i < m.nrows(); i++) - value = std::max(m[i][j], value); - res[j] = value; - } - - return res; -} - -template -Vector r_max(const Matrix& m) -{ - Vector res(m.nrows()); - double value; - for (unsigned int i = 0; i < m.nrows(); i++) - { - value = m[i][0]; - for (unsigned int j = 1; j < m.ncols(); j++) - value = std::max(m[i][j], value); - res[i] = value; - } - - return res; -} - -template -Vector min(const Matrix& m) -{ - Vector res(m.ncols()); - double value; - for (unsigned int j = 0; j < m.ncols(); j++) - { - value = m[0][j]; - for (unsigned int i = 1; i < m.nrows(); i++) - value = std::min(m[i][j], value); - res[j] = value; - } - - return res; -} - -template -Vector r_min(const Matrix& m) -{ - Vector res(m.nrows()); - double value; - for (unsigned int i = 0; i < m.nrows(); i++) - { - value = m[i][0]; - for (unsigned int j = 1; j < m.ncols(); j++) - value = std::min(m[i][j], value); - res[i] = value; - } - - return res; -} - - - -/** - Single element mathematical functions -*/ - -template -Matrix exp(const Matrix&m) -{ - Matrix tmp(m.nrows(), m.ncols()); - - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp[i][j] = exp(m[i][j]); - - return tmp; -} - -template -Matrix mat_sqrt(const Matrix&m) -{ - Matrix tmp(m.nrows(), m.ncols()); - - for (unsigned int i = 0; i < m.nrows(); i++) - for (unsigned int j = 0; j < m.ncols(); j++) - tmp[i][j] = sqrt(m[i][j]); - - return tmp; -} - -/** - Matrix operators -*/ - -template -Matrix kron(const Vector& b, const Vector& a) -{ - Matrix tmp(b.size(), a.size()); - for (unsigned int i = 0; i < b.size(); i++) - for (unsigned int j = 0; j < a.size(); j++) - tmp[i][j] = a[j] * b[i]; - - return tmp; -} - -template -Matrix t(const Matrix& a) -{ - Matrix tmp(a.ncols(), a.nrows()); - for (unsigned int i = 0; i < a.nrows(); i++) - for (unsigned int j = 0; j < a.ncols(); j++) - tmp[j][i] = a[i][j]; - - return tmp; -} - -template -Matrix dot_prod(const Matrix& a, const Matrix& b) -{ - if (a.ncols() != b.nrows()) - throw std::logic_error("Error matrix dot product: dimensions of the matrices are not compatible"); - Matrix tmp(a.nrows(), b.ncols()); - for (unsigned int i = 0; i < tmp.nrows(); i++) - for (unsigned int j = 0; j < tmp.ncols(); j++) - { - tmp[i][j] = (T)0; - for (unsigned int k = 0; k < a.ncols(); k++) - tmp[i][j] += a[i][k] * b[k][j]; - } - - return tmp; -} - -template -Matrix dot_prod(const Matrix& a, const Vector& b) -{ - if (a.ncols() != b.size()) - throw std::logic_error("Error matrix dot product: dimensions of the matrix and the vector are not compatible"); - Matrix tmp(a.nrows(), 1); - for (unsigned int i = 0; i < tmp.nrows(); i++) - { - tmp[i][0] = (T)0; - for (unsigned int k = 0; k < a.ncols(); k++) - tmp[i][0] += a[i][k] * b[k]; - } - - return tmp; -} - -template -Matrix dot_prod(const Vector& a, const Matrix& b) -{ - if (a.size() != b.nrows()) - throw std::logic_error("Error matrix dot product: dimensions of the vector and matrix are not compatible"); - Matrix tmp(1, b.ncols()); - for (unsigned int j = 0; j < tmp.ncols(); j++) - { - tmp[0][j] = (T)0; - for (unsigned int k = 0; k < a.size(); k++) - tmp[0][j] += a[k] * b[k][j]; - } - - return tmp; -} - -template -inline Matrix rank(const Matrix m) -{ - Matrix tmp(m.nrows(), m.ncols()); - for (unsigned int j = 0; j < m.ncols(); j++) - tmp.setColumn(j, rank(m.extractColumn(j))); - - return tmp; -} - -template -inline Matrix r_rank(const Matrix m) -{ - Matrix tmp(m.nrows(), m.ncols()); - for (unsigned int i = 0; i < m.nrows(); i++) - tmp.setRow(i, rank(m.extractRow(i))); - - return tmp; -} - -} // namespace quadprogpp - -#endif // define _ARRAY_HH_ +// $Id: Array.hh 249 2008-11-20 09:58:23Z schaerf $ +// This file is part of EasyLocalpp: a C++ Object-Oriented framework +// aimed at easing the development of Local Search algorithms. +// Copyright (C) 2001--2008 Andrea Schaerf, Luca Di Gaspero. +// +// This software may be modified and distributed under the terms +// of the MIT license. See the LICENSE file for details. + +#if !defined(_ARRAY_HH) +#define _ARRAY_HH + +#include +#include +#include +#include +#include +#include + +namespace quadprogpp { + +enum MType { DIAG }; + +template +class Vector +{ +public: + Vector(); + Vector(const unsigned int n); + Vector(const T& a, const unsigned int n); //initialize to constant value + Vector(const T* a, const unsigned int n); // Initialize to array + Vector(const Vector &rhs); // copy constructor + ~Vector(); // destructor + + inline void set(const T* a, const unsigned int n); + Vector extract(const std::set& indexes) const; + inline T& operator[](const unsigned int& i); //i-th element + inline const T& operator[](const unsigned int& i) const; + + inline unsigned int size() const; + inline void resize(const unsigned int n); + inline void resize(const T& a, const unsigned int n); + + Vector& operator=(const Vector& rhs); //assignment + Vector& operator=(const T& a); //assign a to every element + inline Vector& operator+=(const Vector& rhs); + inline Vector& operator-=(const Vector& rhs); + inline Vector& operator*=(const Vector& rhs); + inline Vector& operator/=(const Vector& rhs); + inline Vector& operator^=(const Vector& rhs); + inline Vector& operator+=(const T& a); + inline Vector& operator-=(const T& a); + inline Vector& operator*=(const T& a); + inline Vector& operator/=(const T& a); + inline Vector& operator^=(const T& a); +private: + unsigned int n; // size of array. upper index is n-1 + T* v; // storage for data +}; + +template +Vector::Vector() + : n(0), v(0) +{} + +template +Vector::Vector(const unsigned int n) + : v(new T[n]) +{ + this->n = n; +} + +template +Vector::Vector(const T& a, const unsigned int n) + : v(new T[n]) +{ + this->n = n; + for (unsigned int i = 0; i < n; i++) + v[i] = a; +} + +template +Vector::Vector(const T* a, const unsigned int n) + : v(new T[n]) +{ + this->n = n; + for (unsigned int i = 0; i < n; i++) + v[i] = *a++; +} + +template +Vector::Vector(const Vector& rhs) + : v(new T[rhs.n]) +{ + this->n = rhs.n; + for (unsigned int i = 0; i < n; i++) + v[i] = rhs[i]; +} + +template +Vector::~Vector() +{ + if (v != 0) + delete[] (v); +} + +template +void Vector::resize(const unsigned int n) +{ + if (n == this->n) + return; + if (v != 0) + delete[] (v); + v = new T[n]; + this->n = n; +} + +template +void Vector::resize(const T& a, const unsigned int n) +{ + resize(n); + for (unsigned int i = 0; i < n; i++) + v[i] = a; +} + + +template +inline Vector& Vector::operator=(const Vector& rhs) +// postcondition: normal assignment via copying has been performed; +// if vector and rhs were different sizes, vector +// has been resized to match the size of rhs +{ + if (this != &rhs) + { + resize(rhs.n); + for (unsigned int i = 0; i < n; i++) + v[i] = rhs[i]; + } + return *this; +} + +template +inline Vector & Vector::operator=(const T& a) //assign a to every element +{ + for (unsigned int i = 0; i < n; i++) + v[i] = a; + return *this; +} + +template +inline T & Vector::operator[](const unsigned int& i) //subscripting +{ + return v[i]; +} + +template +inline const T& Vector::operator[](const unsigned int& i) const //subscripting +{ + return v[i]; +} + +template +inline unsigned int Vector::size() const +{ + return n; +} + +template +inline void Vector::set(const T* a, unsigned int n) +{ + resize(n); + for (unsigned int i = 0; i < n; i++) + v[i] = a[i]; +} + +template +inline Vector Vector::extract(const std::set& indexes) const +{ + Vector tmp(indexes.size()); + unsigned int i = 0; + + for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) + { + if (*el >= n) + throw std::logic_error("Error extracting subvector: the indexes are out of vector bounds"); + tmp[i++] = v[*el]; + } + + return tmp; +} + +template +inline Vector& Vector::operator+=(const Vector& rhs) +{ + if (this->size() != rhs.size()) + throw std::logic_error("Operator+=: vectors have different sizes"); + for (unsigned int i = 0; i < n; i++) + v[i] += rhs[i]; + + return *this; +} + + +template +inline Vector& Vector::operator+=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + v[i] += a; + + return *this; +} + +template +inline Vector operator+(const Vector& rhs) +{ + return rhs; +} + +template +inline Vector operator+(const Vector& lhs, const Vector& rhs) +{ + if (lhs.size() != rhs.size()) + throw std::logic_error("Operator+: vectors have different sizes"); + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] + rhs[i]; + + return tmp; +} + +template +inline Vector operator+(const Vector& lhs, const T& a) +{ + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] + a; + + return tmp; +} + +template +inline Vector operator+(const T& a, const Vector& rhs) +{ + Vector tmp(rhs.size()); + for (unsigned int i = 0; i < rhs.size(); i++) + tmp[i] = a + rhs[i]; + + return tmp; +} + +template +inline Vector& Vector::operator-=(const Vector& rhs) +{ + if (this->size() != rhs.size()) + throw std::logic_error("Operator-=: vectors have different sizes"); + for (unsigned int i = 0; i < n; i++) + v[i] -= rhs[i]; + + return *this; +} + + +template +inline Vector& Vector::operator-=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + v[i] -= a; + + return *this; +} + +template +inline Vector operator-(const Vector& rhs) +{ + return (T)(-1) * rhs; +} + +template +inline Vector operator-(const Vector& lhs, const Vector& rhs) +{ + if (lhs.size() != rhs.size()) + throw std::logic_error("Operator-: vectors have different sizes"); + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] - rhs[i]; + + return tmp; +} + +template +inline Vector operator-(const Vector& lhs, const T& a) +{ + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] - a; + + return tmp; +} + +template +inline Vector operator-(const T& a, const Vector& rhs) +{ + Vector tmp(rhs.size()); + for (unsigned int i = 0; i < rhs.size(); i++) + tmp[i] = a - rhs[i]; + + return tmp; +} + +template +inline Vector& Vector::operator*=(const Vector& rhs) +{ + if (this->size() != rhs.size()) + throw std::logic_error("Operator*=: vectors have different sizes"); + for (unsigned int i = 0; i < n; i++) + v[i] *= rhs[i]; + + return *this; +} + + +template +inline Vector& Vector::operator*=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + v[i] *= a; + + return *this; +} + +template +inline Vector operator*(const Vector& lhs, const Vector& rhs) +{ + if (lhs.size() != rhs.size()) + throw std::logic_error("Operator*: vectors have different sizes"); + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] * rhs[i]; + + return tmp; +} + +template +inline Vector operator*(const Vector& lhs, const T& a) +{ + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] * a; + + return tmp; +} + +template +inline Vector operator*(const T& a, const Vector& rhs) +{ + Vector tmp(rhs.size()); + for (unsigned int i = 0; i < rhs.size(); i++) + tmp[i] = a * rhs[i]; + + return tmp; +} + +template +inline Vector& Vector::operator/=(const Vector& rhs) +{ + if (this->size() != rhs.size()) + throw std::logic_error("Operator/=: vectors have different sizes"); + for (unsigned int i = 0; i < n; i++) + v[i] /= rhs[i]; + + return *this; +} + + +template +inline Vector& Vector::operator/=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + v[i] /= a; + + return *this; +} + +template +inline Vector operator/(const Vector& lhs, const Vector& rhs) +{ + if (lhs.size() != rhs.size()) + throw std::logic_error("Operator/: vectors have different sizes"); + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] / rhs[i]; + + return tmp; +} + +template +inline Vector operator/(const Vector& lhs, const T& a) +{ + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = lhs[i] / a; + + return tmp; +} + +template +inline Vector operator/(const T& a, const Vector& rhs) +{ + Vector tmp(rhs.size()); + for (unsigned int i = 0; i < rhs.size(); i++) + tmp[i] = a / rhs[i]; + + return tmp; +} + +template +inline Vector operator^(const Vector& lhs, const Vector& rhs) +{ + if (lhs.size() != rhs.size()) + throw std::logic_error("Operator^: vectors have different sizes"); + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = pow(lhs[i], rhs[i]); + + return tmp; +} + +template +inline Vector operator^(const Vector& lhs, const T& a) +{ + Vector tmp(lhs.size()); + for (unsigned int i = 0; i < lhs.size(); i++) + tmp[i] = pow(lhs[i], a); + + return tmp; +} + +template +inline Vector operator^(const T& a, const Vector& rhs) +{ + Vector tmp(rhs.size()); + for (unsigned int i = 0; i < rhs.size(); i++) + tmp[i] = pow(a, rhs[i]); + + return tmp; +} + +template +inline Vector& Vector::operator^=(const Vector& rhs) +{ + if (this->size() != rhs.size()) + throw std::logic_error("Operator^=: vectors have different sizes"); + for (unsigned int i = 0; i < n; i++) + v[i] = pow(v[i], rhs[i]); + + return *this; +} + +template +inline Vector& Vector::operator^=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + v[i] = pow(v[i], a); + + return *this; +} + +template +inline bool operator==(const Vector& v, const Vector& w) +{ + if (v.size() != w.size()) + throw std::logic_error("Vectors of different size are not confrontable"); + for (unsigned i = 0; i < v.size(); i++) + if (v[i] != w[i]) + return false; + return true; +} + +template +inline bool operator!=(const Vector& v, const Vector& w) +{ + if (v.size() != w.size()) + throw std::logic_error("Vectors of different size are not confrontable"); + for (unsigned i = 0; i < v.size(); i++) + if (v[i] != w[i]) + return true; + return false; +} + +template +inline bool operator<(const Vector& v, const Vector& w) +{ + if (v.size() != w.size()) + throw std::logic_error("Vectors of different size are not confrontable"); + for (unsigned i = 0; i < v.size(); i++) + if (v[i] >= w[i]) + return false; + return true; +} + +template +inline bool operator<=(const Vector& v, const Vector& w) +{ + if (v.size() != w.size()) + throw std::logic_error("Vectors of different size are not confrontable"); + for (unsigned i = 0; i < v.size(); i++) + if (v[i] > w[i]) + return false; + return true; +} + +template +inline bool operator>(const Vector& v, const Vector& w) +{ + if (v.size() != w.size()) + throw std::logic_error("Vectors of different size are not confrontable"); + for (unsigned i = 0; i < v.size(); i++) + if (v[i] <= w[i]) + return false; + return true; +} + +template +inline bool operator>=(const Vector& v, const Vector& w) +{ + if (v.size() != w.size()) + throw std::logic_error("Vectors of different size are not confrontable"); + for (unsigned i = 0; i < v.size(); i++) + if (v[i] < w[i]) + return false; + return true; +} + +/** + Input/Output +*/ +template +inline std::ostream& operator<<(std::ostream& os, const Vector& v) +{ + os << std::endl << v.size() << std::endl; + for (unsigned int i = 0; i < v.size() - 1; i++) + os << std::setw(20) << std::setprecision(16) << v[i] << ", "; + os << std::setw(20) << std::setprecision(16) << v[v.size() - 1] << std::endl; + + return os; +} + +template +std::istream& operator>>(std::istream& is, Vector& v) +{ + int elements; + char comma; + is >> elements; + v.resize(elements); + for (unsigned int i = 0; i < elements; i++) + is >> v[i] >> comma; + + return is; +} + +/** + Index utilities +*/ + +std::set seq(unsigned int s, unsigned int e); + +std::set singleton(unsigned int i); + +template +class CanonicalBaseVector : public Vector +{ +public: + CanonicalBaseVector(unsigned int i, unsigned int n); + inline void reset(unsigned int i); +private: + unsigned int e; +}; + +template +CanonicalBaseVector::CanonicalBaseVector(unsigned int i, unsigned int n) + : Vector((T)0, n), e(i) +{ (*this)[e] = (T)1; } + +template +inline void CanonicalBaseVector::reset(unsigned int i) +{ + (*this)[e] = (T)0; + e = i; + (*this)[e] = (T)1; +} + +#include + +template +inline T sum(const Vector& v) +{ + T tmp = (T)0; + for (unsigned int i = 0; i < v.size(); i++) + tmp += v[i]; + + return tmp; +} + +template +inline T prod(const Vector& v) +{ + T tmp = (T)1; + for (unsigned int i = 0; i < v.size(); i++) + tmp *= v[i]; + + return tmp; +} + +template +inline T mean(const Vector& v) +{ + T sum = (T)0; + for (unsigned int i = 0; i < v.size(); i++) + sum += v[i]; + return sum / v.size(); +} + +template +inline T median(const Vector& v) +{ + Vector tmp = sort(v); + if (v.size() % 2 == 1) // it is an odd-sized vector + return tmp[v.size() / 2]; + else + return 0.5 * (tmp[v.size() / 2 - 1] + tmp[v.size() / 2]); +} + +template +inline T stdev(const Vector& v, bool sample_correction = false) +{ + return sqrt(var(v, sample_correction)); +} + +template +inline T var(const Vector& v, bool sample_correction = false) +{ + T sum = (T)0, ssum = (T)0; + unsigned int n = v.size(); + for (unsigned int i = 0; i < n; i++) + { + sum += v[i]; + ssum += (v[i] * v[i]); + } + if (!sample_correction) + return (ssum / n) - (sum / n) * (sum / n); + else + return n * ((ssum / n) - (sum / n) * (sum / n)) / (n - 1); +} + +template +inline T max(const Vector& v) +{ + T value = v[0]; + for (unsigned int i = 1; i < v.size(); i++) + value = std::max(v[i], value); + + return value; +} + +template +inline T min(const Vector& v) +{ + T value = v[0]; + for (unsigned int i = 1; i < v.size(); i++) + value = std::min(v[i], value); + + return value; +} + +template +inline unsigned int index_max(const Vector& v) +{ + unsigned int max = 0; + for (unsigned int i = 1; i < v.size(); i++) + if (v[i] > v[max]) + max = i; + + return max; +} + +template +inline unsigned int index_min(const Vector& v) +{ + unsigned int min = 0; + for (unsigned int i = 1; i < v.size(); i++) + if (v[i] < v[min]) + min = i; + + return min; +} + + +template +inline T dot_prod(const Vector& a, const Vector& b) +{ + T sum = (T)0; + if (a.size() != b.size()) + throw std::logic_error("Dotprod error: the vectors are not the same size"); + for (unsigned int i = 0; i < a.size(); i++) + sum += a[i] * b[i]; + + return sum; +} + +/** + Single element mathematical functions +*/ + +template +inline Vector exp(const Vector& v) +{ + Vector tmp(v.size()); + for (unsigned int i = 0; i < v.size(); i++) + tmp[i] = exp(v[i]); + + return tmp; +} + +template +inline Vector log(const Vector& v) +{ + Vector tmp(v.size()); + for (unsigned int i = 0; i < v.size(); i++) + tmp[i] = log(v[i]); + + return tmp; +} + +template +inline Vector vec_sqrt(const Vector& v) +{ + Vector tmp(v.size()); + for (unsigned int i = 0; i < v.size(); i++) + tmp[i] = sqrt(v[i]); + + return tmp; +} + +template +inline Vector pow(const Vector& v, double a) +{ + Vector tmp(v.size()); + for (unsigned int i = 0; i < v.size(); i++) + tmp[i] = pow(v[i], a); + + return tmp; +} + +template +inline Vector abs(const Vector& v) +{ + Vector tmp(v.size()); + for (unsigned int i = 0; i < v.size(); i++) + tmp[i] = (T)fabs(v[i]); + + return tmp; +} + +template +inline Vector sign(const Vector& v) +{ + Vector tmp(v.size()); + for (unsigned int i = 0; i < v.size(); i++) + tmp[i] = v[i] > 0 ? +1 : v[i] == 0 ? 0 : -1; + + return tmp; +} + +template +inline unsigned int partition(Vector& v, unsigned int begin, unsigned int end) +{ + unsigned int i = begin + 1, j = begin + 1; + T pivot = v[begin]; + while (j <= end) + { + if (v[j] < pivot) { + std::swap(v[i], v[j]); + i++; + } + j++; + } + v[begin] = v[i - 1]; + v[i - 1] = pivot; + return i - 2; +} + + +template +inline void quicksort(Vector& v, unsigned int begin, unsigned int end) +{ + if (end > begin) + { + unsigned int index = partition(v, begin, end); + quicksort(v, begin, index); + quicksort(v, index + 2, end); + } +} + +template +inline Vector sort(const Vector& v) +{ + Vector tmp(v); + + quicksort(tmp, 0, tmp.size() - 1); + + return tmp; +} + +template +inline Vector rank(const Vector& v) +{ + Vector tmp(v); + Vector tmp_rank(0.0, v.size()); + + for (unsigned int i = 0; i < tmp.size(); i++) + { + unsigned int smaller = 0, equal = 0; + for (unsigned int j = 0; j < tmp.size(); j++) + if (i == j) + continue; + else + if (tmp[j] < tmp[i]) + smaller++; + else if (tmp[j] == tmp[i]) + equal++; + tmp_rank[i] = smaller + 1; + if (equal > 0) + { + for (unsigned int j = 1; j <= equal; j++) + tmp_rank[i] += smaller + 1 + j; + tmp_rank[i] /= (double)(equal + 1); + } + } + + return tmp_rank; +} + +//enum MType { DIAG }; + +template +class Matrix +{ +public: + Matrix(); // Default constructor + Matrix(const unsigned int n, const unsigned int m); // Construct a n x m matrix + Matrix(const T& a, const unsigned int n, const unsigned int m); // Initialize the content to constant a + Matrix(MType t, const T& a, const T& o, const unsigned int n, const unsigned int m); + Matrix(MType t, const Vector& v, const T& o, const unsigned int n, const unsigned int m); + Matrix(const T* a, const unsigned int n, const unsigned int m); // Initialize to array + Matrix(const Matrix& rhs); // Copy constructor + ~Matrix(); // destructor + + inline T* operator[](const unsigned int& i) { return v[i]; } // Subscripting: row i + inline const T* operator[](const unsigned int& i) const { return v[i]; }; // const subsctipting + + inline void resize(const unsigned int n, const unsigned int m); + inline void resize(const T& a, const unsigned int n, const unsigned int m); + + + inline Vector extractRow(const unsigned int i) const; + inline Vector extractColumn(const unsigned int j) const; + inline Vector extractDiag() const; + inline Matrix extractRows(const std::set& indexes) const; + inline Matrix extractColumns(const std::set& indexes) const; + inline Matrix extract(const std::set& r_indexes, const std::set& c_indexes) const; + + inline void set(const T* a, unsigned int n, unsigned int m); + inline void set(const std::set& r_indexes, const std::set& c_indexes, const Matrix& m); + inline void setRow(const unsigned int index, const Vector& v); + inline void setRow(const unsigned int index, const Matrix& v); + inline void setRows(const std::set& indexes, const Matrix& m); + inline void setColumn(const unsigned int index, const Vector& v); + inline void setColumn(const unsigned int index, const Matrix& v); + inline void setColumns(const std::set& indexes, const Matrix& m); + + + inline unsigned int nrows() const { return n; } // number of rows + inline unsigned int ncols() const { return m; } // number of columns + + inline Matrix& operator=(const Matrix& rhs); // Assignment operator + inline Matrix& operator=(const T& a); // Assign to every element value a + inline Matrix& operator+=(const Matrix& rhs); + inline Matrix& operator-=(const Matrix& rhs); + inline Matrix& operator*=(const Matrix& rhs); + inline Matrix& operator/=(const Matrix& rhs); + inline Matrix& operator^=(const Matrix& rhs); + inline Matrix& operator+=(const T& a); + inline Matrix& operator-=(const T& a); + inline Matrix& operator*=(const T& a); + inline Matrix& operator/=(const T& a); + inline Matrix& operator^=(const T& a); + inline operator Vector(); +private: + unsigned int n; // number of rows + unsigned int m; // number of columns + T **v; // storage for data +}; + +template +Matrix::Matrix() + : n(0), m(0), v(0) +{} + +template +Matrix::Matrix(unsigned int n, unsigned int m) + : v(new T*[n]) +{ + this->n = n; this->m = m; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; +} + +template +Matrix::Matrix(const T& a, unsigned int n, unsigned int m) + : v(new T*[n]) +{ + this->n = n; this->m = m; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = a; +} + +template +Matrix::Matrix(const T* a, unsigned int n, unsigned int m) + : v(new T*[n]) +{ + this->n = n; this->m = m; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = *a++; +} + +template +Matrix::Matrix(MType t, const T& a, const T& o, unsigned int n, unsigned int m) + : v(new T*[n]) +{ + this->n = n; this->m = m; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; + switch (t) + { + case DIAG: + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + if (i != j) + v[i][j] = o; + else + v[i][j] = a; + break; + default: + throw std::logic_error("Matrix type not supported"); + } +} + +template +Matrix::Matrix(MType t, const Vector& a, const T& o, unsigned int n, unsigned int m) + : v(new T*[n]) +{ + this->n = n; this->m = m; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; + switch (t) + { + case DIAG: + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + if (i != j) + v[i][j] = o; + else + v[i][j] = a[i]; + break; + default: + throw std::logic_error("Matrix type not supported"); + } +} + +template +Matrix::Matrix(const Matrix& rhs) + : v(new T*[rhs.n]) +{ + n = rhs.n; m = rhs.m; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = rhs[i][j]; +} + +template +Matrix::~Matrix() +{ + if (v != 0) { + delete[] (v[0]); + delete[] (v); + } +} + +template +inline Matrix& Matrix::operator=(const Matrix &rhs) +// postcondition: normal assignment via copying has been performed; +// if matrix and rhs were different sizes, matrix +// has been resized to match the size of rhs +{ + if (this != &rhs) + { + resize(rhs.n, rhs.m); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = rhs[i][j]; + } + return *this; +} + +template +inline Matrix& Matrix::operator=(const T& a) // assign a to every element +{ + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = a; + return *this; +} + + +template +inline void Matrix::resize(const unsigned int n, const unsigned int m) +{ + if (n == this->n && m == this->m) + return; + if (v != 0) + { + delete[] (v[0]); + delete[] (v); + } + this->n = n; this->m = m; + v = new T*[n]; + v[0] = new T[m * n]; + for (unsigned int i = 1; i < n; i++) + v[i] = v[i - 1] + m; +} + +template +inline void Matrix::resize(const T& a, const unsigned int n, const unsigned int m) +{ + resize(n, m); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = a; +} + + + +template +inline Vector Matrix::extractRow(const unsigned int i) const +{ + if (i >= n) + throw std::logic_error("Error in extractRow: trying to extract a row out of matrix bounds"); + Vector tmp(v[i], m); + + return tmp; +} + +template +inline Vector Matrix::extractColumn(const unsigned int j) const +{ + if (j >= m) + throw std::logic_error("Error in extractRow: trying to extract a row out of matrix bounds"); + Vector tmp(n); + + for (unsigned int i = 0; i < n; i++) + tmp[i] = v[i][j]; + + return tmp; +} + +template +inline Vector Matrix::extractDiag() const +{ + unsigned int d = std::min(n, m); + + Vector tmp(d); + + for (unsigned int i = 0; i < d; i++) + tmp[i] = v[i][i]; + + return tmp; + +} + +template +inline Matrix Matrix::extractRows(const std::set& indexes) const +{ + Matrix tmp(indexes.size(), m); + unsigned int i = 0; + + for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) + { + for (unsigned int j = 0; j < m; j++) + { + if (*el >= n) + throw std::logic_error("Error extracting rows: the indexes are out of matrix bounds"); + tmp[i][j] = v[*el][j]; + } + i++; + } + + return tmp; +} + +template +inline Matrix Matrix::extractColumns(const std::set& indexes) const +{ + Matrix tmp(n, indexes.size()); + unsigned int j = 0; + + for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) + { + for (unsigned int i = 0; i < n; i++) + { + if (*el >= m) + throw std::logic_error("Error extracting columns: the indexes are out of matrix bounds"); + tmp[i][j] = v[i][*el]; + } + j++; + } + + return tmp; +} + +template +inline Matrix Matrix::extract(const std::set& r_indexes, const std::set& c_indexes) const +{ + Matrix tmp(r_indexes.size(), c_indexes.size()); + unsigned int i = 0, j; + + for (std::set::const_iterator r_el = r_indexes.begin(); r_el != r_indexes.end(); r_el++) + { + if (*r_el >= n) + throw std::logic_error("Error extracting submatrix: the indexes are out of matrix bounds"); + j = 0; + for (std::set::const_iterator c_el = c_indexes.begin(); c_el != c_indexes.end(); c_el++) + { + if (*c_el >= m) + throw std::logic_error("Error extracting rows: the indexes are out of matrix bounds"); + tmp[i][j] = v[*r_el][*c_el]; + j++; + } + i++; + } + + return tmp; +} + +template +inline void Matrix::setRow(unsigned int i, const Vector& a) +{ + if (i >= n) + throw std::logic_error("Error in setRow: trying to set a row out of matrix bounds"); + if (this->m != a.size()) + throw std::logic_error("Error setting matrix row: ranges are not compatible"); + for (unsigned int j = 0; j < ncols(); j++) + v[i][j] = a[j]; +} + +template +inline void Matrix::setRow(unsigned int i, const Matrix& a) +{ + if (i >= n) + throw std::logic_error("Error in setRow: trying to set a row out of matrix bounds"); + if (this->m != a.ncols()) + throw std::logic_error("Error setting matrix column: ranges are not compatible"); + if (a.nrows() != 1) + throw std::logic_error("Error setting matrix column with a non-row matrix"); + for (unsigned int j = 0; j < ncols(); j++) + v[i][j] = a[0][j]; +} + +template +inline void Matrix::setRows(const std::set& indexes, const Matrix& m) +{ + unsigned int i = 0; + + if (indexes.size() != m.nrows() || this->m != m.ncols()) + throw std::logic_error("Error setting matrix rows: ranges are not compatible"); + for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) + { + for (unsigned int j = 0; j < ncols(); j++) + { + if (*el >= n) + throw std::logic_error("Error in setRows: trying to set a row out of matrix bounds"); + v[*el][j] = m[i][j]; + } + i++; + } +} + +template +inline void Matrix::setColumn(unsigned int j, const Vector& a) +{ + if (j >= m) + throw std::logic_error("Error in setColumn: trying to set a column out of matrix bounds"); + if (this->n != a.size()) + throw std::logic_error("Error setting matrix column: ranges are not compatible"); + for (unsigned int i = 0; i < nrows(); i++) + v[i][j] = a[i]; +} + +template +inline void Matrix::setColumn(unsigned int j, const Matrix& a) +{ + if (j >= m) + throw std::logic_error("Error in setColumn: trying to set a column out of matrix bounds"); + if (this->n != a.nrows()) + throw std::logic_error("Error setting matrix column: ranges are not compatible"); + if (a.ncols() != 1) + throw std::logic_error("Error setting matrix column with a non-column matrix"); + for (unsigned int i = 0; i < nrows(); i++) + v[i][j] = a[i][0]; +} + + +template +inline void Matrix::setColumns(const std::set& indexes, const Matrix& a) +{ + unsigned int j = 0; + + if (indexes.size() != a.ncols() || this->n != a.nrows()) + throw std::logic_error("Error setting matrix columns: ranges are not compatible"); + for (std::set::const_iterator el = indexes.begin(); el != indexes.end(); el++) + { + for (unsigned int i = 0; i < nrows(); i++) + { + if (*el >= m) + throw std::logic_error("Error in setColumns: trying to set a column out of matrix bounds"); + v[i][*el] = a[i][j]; + } + j++; + } +} + +template +inline void Matrix::set(const std::set& r_indexes, const std::set& c_indexes, const Matrix& a) +{ + unsigned int i = 0, j; + if (c_indexes.size() != a.ncols() || r_indexes.size() != a.nrows()) + throw std::logic_error("Error setting matrix elements: ranges are not compatible"); + + for (std::set::const_iterator r_el = r_indexes.begin(); r_el != r_indexes.end(); r_el++) + { + if (*r_el >= n) + throw std::logic_error("Error in set: trying to set a row out of matrix bounds"); + j = 0; + for (std::set::const_iterator c_el = c_indexes.begin(); c_el != c_indexes.end(); c_el++) + { + if (*c_el >= m) + throw std::logic_error("Error in set: trying to set a column out of matrix bounds"); + v[*r_el][*c_el] = a[i][j]; + j++; + } + i++; + } +} + +template +inline void Matrix::set(const T* a, unsigned int n, unsigned int m) +{ + if (this->n != n || this->m != m) + resize(n, m); + unsigned int k = 0; + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = a[k++]; +} + + +template +Matrix operator+(const Matrix& rhs) +{ + return rhs; +} + +template +Matrix operator+(const Matrix& lhs, const Matrix& rhs) +{ + if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) + throw std::logic_error("Operator+: matrices have different sizes"); + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] + rhs[i][j]; + + return tmp; +} + +template +Matrix operator+(const Matrix& lhs, const T& a) +{ + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] + a; + + return tmp; +} + +template +Matrix operator+(const T& a, const Matrix& rhs) +{ + Matrix tmp(rhs.nrows(), rhs.ncols()); + for (unsigned int i = 0; i < rhs.nrows(); i++) + for (unsigned int j = 0; j < rhs.ncols(); j++) + tmp[i][j] = a + rhs[i][j]; + + return tmp; +} + +template +inline Matrix& Matrix::operator+=(const Matrix& rhs) +{ + if (m != rhs.ncols() || n != rhs.nrows()) + throw std::logic_error("Operator+=: matrices have different sizes"); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] += rhs[i][j]; + + return *this; +} + +template +inline Matrix& Matrix::operator+=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] += a; + + return *this; +} + +template +Matrix operator-(const Matrix& rhs) +{ + return (T)(-1) * rhs; +} + +template +Matrix operator-(const Matrix& lhs, const Matrix& rhs) +{ + if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) + throw std::logic_error("Operator-: matrices have different sizes"); + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] - rhs[i][j]; + + return tmp; +} + +template +Matrix operator-(const Matrix& lhs, const T& a) +{ + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] - a; + + return tmp; +} + +template +Matrix operator-(const T& a, const Matrix& rhs) +{ + Matrix tmp(rhs.nrows(), rhs.ncols()); + for (unsigned int i = 0; i < rhs.nrows(); i++) + for (unsigned int j = 0; j < rhs.ncols(); j++) + tmp[i][j] = a - rhs[i][j]; + + return tmp; +} + +template +inline Matrix& Matrix::operator-=(const Matrix& rhs) +{ + if (m != rhs.ncols() || n != rhs.nrows()) + throw std::logic_error("Operator-=: matrices have different sizes"); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] -= rhs[i][j]; + + return *this; +} + +template +inline Matrix& Matrix::operator-=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] -= a; + + return *this; +} + +template +Matrix operator*(const Matrix& lhs, const Matrix& rhs) +{ + if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) + throw std::logic_error("Operator*: matrices have different sizes"); + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] * rhs[i][j]; + + return tmp; +} + +template +Matrix operator*(const Matrix& lhs, const T& a) +{ + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] * a; + + return tmp; +} + +template +Matrix operator*(const T& a, const Matrix& rhs) +{ + Matrix tmp(rhs.nrows(), rhs.ncols()); + for (unsigned int i = 0; i < rhs.nrows(); i++) + for (unsigned int j = 0; j < rhs.ncols(); j++) + tmp[i][j] = a * rhs[i][j]; + + return tmp; +} + +template +inline Matrix& Matrix::operator*=(const Matrix& rhs) +{ + if (m != rhs.ncols() || n != rhs.nrows()) + throw std::logic_error("Operator*=: matrices have different sizes"); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] *= rhs[i][j]; + + return *this; +} + +template +inline Matrix& Matrix::operator*=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] *= a; + + return *this; +} + +template +Matrix operator/(const Matrix& lhs, const Matrix& rhs) +{ + if (lhs.ncols() != rhs.ncols() || lhs.nrows() != rhs.nrows()) + throw std::logic_error("Operator+: matrices have different sizes"); + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] / rhs[i][j]; + + return tmp; +} + +template +Matrix operator/(const Matrix& lhs, const T& a) +{ + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = lhs[i][j] / a; + + return tmp; +} + +template +Matrix operator/(const T& a, const Matrix& rhs) +{ + Matrix tmp(rhs.nrows(), rhs.ncols()); + for (unsigned int i = 0; i < rhs.nrows(); i++) + for (unsigned int j = 0; j < rhs.ncols(); j++) + tmp[i][j] = a / rhs[i][j]; + + return tmp; +} + +template +inline Matrix& Matrix::operator/=(const Matrix& rhs) +{ + if (m != rhs.ncols() || n != rhs.nrows()) + throw std::logic_error("Operator+=: matrices have different sizes"); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] /= rhs[i][j]; + + return *this; +} + +template +inline Matrix& Matrix::operator/=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] /= a; + + return *this; +} + +template +Matrix operator^(const Matrix& lhs, const T& a) +{ + Matrix tmp(lhs.nrows(), lhs.ncols()); + for (unsigned int i = 0; i < lhs.nrows(); i++) + for (unsigned int j = 0; j < lhs.ncols(); j++) + tmp[i][j] = pow(lhs[i][j], a); + + return tmp; +} + +template +inline Matrix& Matrix::operator^=(const Matrix& rhs) +{ + if (m != rhs.ncols() || n != rhs.nrows()) + throw std::logic_error("Operator^=: matrices have different sizes"); + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = pow(v[i][j], rhs[i][j]); + + return *this; +} + + +template +inline Matrix& Matrix::operator^=(const T& a) +{ + for (unsigned int i = 0; i < n; i++) + for (unsigned int j = 0; j < m; j++) + v[i][j] = pow(v[i][j], a); + + return *this; +} + +template +inline Matrix::operator Vector() +{ + if (n > 1 && m > 1) + throw std::logic_error("Error matrix cast to vector: trying to cast a multi-dimensional matrix"); + if (n == 1) + return extractRow(0); + else + return extractColumn(0); +} + +template +inline bool operator==(const Matrix& a, const Matrix& b) +{ + if (a.nrows() != b.nrows() || a.ncols() != b.ncols()) + throw std::logic_error("Matrices of different size are not confrontable"); + for (unsigned i = 0; i < a.nrows(); i++) + for (unsigned j = 0; j < a.ncols(); j++) + if (a[i][j] != b[i][j]) + return false; + return true; +} + +template +inline bool operator!=(const Matrix& a, const Matrix& b) +{ + if (a.nrows() != b.nrows() || a.ncols() != b.ncols()) + throw std::logic_error("Matrices of different size are not confrontable"); + for (unsigned i = 0; i < a.nrows(); i++) + for (unsigned j = 0; j < a.ncols(); j++) + if (a[i][j] != b[i][j]) + return true; + return false; +} + + + +/** + Input/Output +*/ +template +std::ostream& operator<<(std::ostream& os, const Matrix& m) +{ + os << std::endl << m.nrows() << " " << m.ncols() << std::endl; + for (unsigned int i = 0; i < m.nrows(); i++) + { + for (unsigned int j = 0; j < m.ncols() - 1; j++) + os << std::setw(20) << std::setprecision(16) << m[i][j] << ", "; + os << std::setw(20) << std::setprecision(16) << m[i][m.ncols() - 1] << std::endl; + } + + return os; +} + +template +std::istream& operator>>(std::istream& is, Matrix& m) +{ + int rows, cols; + char comma; + is >> rows >> cols; + m.resize(rows, cols); + for (unsigned int i = 0; i < rows; i++) + for (unsigned int j = 0; j < cols; j++) + is >> m[i][j] >> comma; + + return is; +} + +template +T sign(const T& v) +{ + if (v >= (T)0.0) + return (T)1.0; + else + return (T)-1.0; +} + +template +T dist(const T& a, const T& b) +{ + T abs_a = (T)fabs(a), abs_b = (T)fabs(b); + if (abs_a > abs_b) + return abs_a * sqrt((T)1.0 + (abs_b / abs_a) * (abs_b / abs_a)); + else + return (abs_b == (T)0.0 ? (T)0.0 : abs_b * sqrt((T)1.0 + (abs_a / abs_b) * (abs_a / abs_b))); +} + +template +void svd(const Matrix& A, Matrix& U, Vector& W, Matrix& V) +{ + int m = A.nrows(), n = A.ncols(), i, j, k, l, jj, nm; + const unsigned int max_its = 30; + bool flag; + Vector rv1(n); + U = A; + W.resize(n); + V.resize(n, n); + T anorm, c, f, g, h, s, scale, x, y, z; + g = scale = anorm = (T)0.0; + + // Householder reduction to bidiagonal form + for (i = 0; i < n; i++) + { + l = i + 1; + rv1[i] = scale * g; + g = s = scale = (T)0.0; + if (i < m) + { + for (k = i; k < m; k++) + scale += fabs(U[k][i]); + if (scale != (T)0.0) + { + for (k = i; k < m; k++) + { + U[k][i] /= scale; + s += U[k][i] * U[k][i]; + } + f = U[i][i]; + g = -sign(f) * sqrt(s); + h = f * g - s; + U[i][i] = f - g; + for (j = l; j < n; j++) + { + s = (T)0.0; + for (k = i; k < m; k++) + s += U[k][i] * U[k][j]; + f = s / h; + for (k = i; k < m; k++) + U[k][j] += f * U[k][i]; + } + for (k = i; k < m; k++) + U[k][i] *= scale; + } + } + W[i] = scale * g; + g = s = scale = (T)0.0; + if (i < m && i != n - 1) + { + for (k = l; k < n; k++) + scale += fabs(U[i][k]); + if (scale != (T)0.0) + { + for (k = l; k < n; k++) + { + U[i][k] /= scale; + s += U[i][k] * U[i][k]; + } + f = U[i][l]; + g = -sign(f) * sqrt(s); + h = f * g - s; + U[i][l] = f - g; + for (k = l; k = 0; i--) + { + if (i < n - 1) + { + if (g != (T)0.0) + { + for (j = l; j < n; j++) + V[j][i] = (U[i][j] / U[i][l]) / g; + for (j = l; j < n; j++) + { + s = (T)0.0; + for (k = l; k < n; k++) + s += U[i][k] * V[k][j]; + for (k = l; k < n; k++) + V[k][j] += s * V[k][i]; + } + } + for (j = l; j < n; j++) + V[i][j] = V[j][i] = (T)0.0; + } + V[i][i] = (T)1.0; + g = rv1[i]; + l = i; + } + // Accumulation of left-hand transformations + for (i = std::min(m, n) - 1; i >= 0; i--) + { + l = i + 1; + g = W[i]; + for (j = l; j < n; j++) + U[i][j] = (T)0.0; + if (g != (T)0.0) + { + g = (T)1.0 / g; + for (j = l; j < n; j++) + { + s = (T)0.0; + for (k = l; k < m; k++) + s += U[k][i] * U[k][j]; + f = (s / U[i][i]) * g; + for (k = i; k < m; k++) + U[k][j] += f * U[k][i]; + } + for (j = i; j < m; j++) + U[j][i] *= g; + } + else + for (j = i; j < m; j++) + U[j][i] = (T)0.0; + U[i][i]++; + } + // Diagonalization of the bidiagonal form: loop over singular values, and over allowed iterations. + for (k = n - 1; k >= 0; k--) + { + for (unsigned int its = 0; its < max_its; its++) + { + flag = true; + for (l = k; l >= 0; l--) + { // Test for splitting + nm = l - 1; // Note that rV[0] is always zero + if ((T)(fabs(rv1[l]) + anorm) == anorm) + { + flag = false; + break; + } + if ((T)(fabs(W[nm]) + anorm) == anorm) + break; + } + if (flag) + { + // Cancellation of rv1[l], if l > 0 FIXME: it was l > 1 in NR + c = (T)0.0; + s = (T)1.0; + for (i = l; i <= k; i++) + { + f = s * rv1[i]; + rv1[i] *= c; + if ((T)(fabs(f) + anorm) == anorm) + break; + g = W[i]; + h = dist(f, g); + W[i] = h; + h = (T)1.0 / h; + c = g * h; + s = -f * h; + for (j = 0; j < m; j++) + { + y = U[j][nm]; + z = U[j][i]; + U[j][nm] = y * c + z * s; + U[j][i] = z * c - y * s; + } + } + } + z = W[k]; + if (l == k) + { // Convergence + if (z < (T)0.0) + { // Singular value is made nonnegative + W[k] = -z; + for (j = 0; j < n; j++) + V[j][k] = -V[j][k]; + } + break; + } + if (its == max_its) + throw std::logic_error("Error svd: no convergence in the maximum number of iterations"); + x = W[l]; + nm = k - 1; + y = W[nm]; + g = rv1[nm]; + h = rv1[k]; + f = ((y - z) * (y + z) + (g - h) * (g + h)) / (2.0 * h * y); + g = dist(f, (T)1.0); + f = ((x - z) * (x + z) + h * ((y / (f + sign(f)*fabs(g))) - h)) / x; + c = s = (T)1.0; // Next QR transformation + for (j = l; j <= nm; j++) + { + i = j + 1; + g = rv1[i]; + y = W[i]; + h = s * g; + g *= c; + z = dist(f, h); + rv1[j] = z; + c = f / z; + s = h / z; + f = x * c + g * s; + g = g * c - x * s; + h = y * s; + y *= c; + for (jj = 0; jj < n; jj++) + { + x = V[jj][j]; + z = V[jj][i]; + V[jj][j] = x * c + z * s; + V[jj][i] = z * c - x * s; + } + z = dist(f, h); + W[j] = z; + if (z != 0) // Rotation can be arbitrary if z = 0 + { + z = (T)1.0 / z; + c = f * z; + s = h * z; + } + f = c * g + s * y; + x = c * y - s * g; + for (jj = 0; jj < m; jj++) + { + y = U[jj][j]; + z = U[jj][i]; + U[jj][j] = y * c + z * s; + U[jj][i] = z * c - y * s; + } + } + rv1[l] = (T)0.0; + rv1[k] = f; + W[k] = x; + } + } +} + +template +Matrix pinv(const Matrix& A) +{ + Matrix U, V, x, tmp(A.ncols(), A.nrows()); + Vector W; + CanonicalBaseVector e(0, A.nrows()); + svd(A, U, W, V); + for (unsigned int i = 0; i < A.nrows(); i++) + { + e.reset(i); + tmp.setColumn(i, dot_prod(dot_prod(dot_prod(V, Matrix(DIAG, 1.0 / W, 0.0, W.size(), W.size())), t(U)), e)); + } + + return tmp; +} + +template +int lu(const Matrix& A, Matrix& LU, Vector& index) +{ + if (A.ncols() != A.nrows()) + throw std::logic_error("Error in LU decomposition: matrix must be squared"); + int i, p, j, k, n = A.ncols(), ex; + T val, tmp; + Vector d(n); + LU = A; + index.resize(n); + + ex = 1; + for (i = 0; i < n; i++) + { + index[i] = i; + val = (T)0.0; + for (j = 0; j < n; j++) + val = std::max(val, (T)fabs(LU[i][j])); + if (val == (T)0.0) + std::logic_error("Error in LU decomposition: matrix was singular"); + d[i] = val; + } + + for (k = 0; k < n - 1; k++) + { + p = k; + val = fabs(LU[k][k]) / d[k]; + for (i = k + 1; i < n; i++) + { + tmp = fabs(LU[i][k]) / d[i]; + if (tmp > val) + { + val = tmp; + p = i; + } + } + if (val == (T)0.0) + std::logic_error("Error in LU decomposition: matrix was singular"); + if (p > k) + { + ex = -ex; + std::swap(index[k], index[p]); + std::swap(d[k], d[p]); + for (j = 0; j < n; j++) + std::swap(LU[k][j], LU[p][j]); + } + + for (i = k + 1; i < n; i++) + { + LU[i][k] /= LU[k][k]; + for (j = k + 1; j < n; j++) + LU[i][j] -= LU[i][k] * LU[k][j]; + } + } + if (LU[n - 1][n - 1] == (T)0.0) + std::logic_error("Error in LU decomposition: matrix was singular"); + + return ex; +} + +template +Vector lu_solve(const Matrix& LU, const Vector& b, Vector& index) +{ + if (LU.ncols() != LU.nrows()) + throw std::logic_error("Error in LU solve: LU matrix should be squared"); + unsigned int n = LU.ncols(); + if (b.size() != n) + throw std::logic_error("Error in LU solve: b vector must be of the same dimensions of LU matrix"); + Vector x((T)0.0, n); + int i, j, p; + T sum; + + p = index[0]; + x[0] = b[p]; + + for (i = 1; i < n; i++) + { + sum = (T)0.0; + for (j = 0; j < i; j++) + sum += LU[i][j] * x[j]; + p = index[i]; + x[i] = b[p] - sum; + } + x[n - 1] /= LU[n - 1][n - 1]; + for (i = n - 2; i >= 0; i--) + { + sum = (T)0.0; + for (j = i + 1; j < n; j++) + sum += LU[i][j] * x[j]; + x[i] = (x[i] - sum) / LU[i][i]; + } + return x; +} + +template +void lu_solve(const Matrix& LU, Vector& x, const Vector& b, Vector& index) +{ + x = lu_solve(LU, b, index); +} + +template +Matrix lu_inverse(const Matrix& A) +{ + if (A.ncols() != A.nrows()) + throw std::logic_error("Error in LU invert: matrix must be squared"); + unsigned int n = A.ncols(); + Matrix A1(n, n), LU; + Vector index; + + lu(A, LU, index); + CanonicalBaseVector e(0, n); + for (unsigned i = 0; i < n; i++) + { + e.reset(i); + A1.setColumn(i, lu_solve(LU, e, index)); + } + + return A1; +} + +template +T lu_det(const Matrix& A) +{ + if (A.ncols() != A.nrows()) + throw std::logic_error("Error in LU determinant: matrix must be squared"); + unsigned int d; + Matrix LU; + Vector index; + + d = lu(A, LU, index); + + return d * prod(LU.extractDiag()); +} + +template +void cholesky(const Matrix A, Matrix& LL) +{ + if (A.ncols() != A.nrows()) + throw std::logic_error("Error in Cholesky decomposition: matrix must be squared"); + int n = A.ncols(); + double sum; + LL = A; + + for (unsigned int i = 0; i < n; i++) + { + for (unsigned int j = i; j < n; j++) + { + sum = LL[i][j]; + for (int k = i - 1; k >= 0; k--) + sum -= LL[i][k] * LL[j][k]; + if (i == j) + { + if (sum <= 0.0) + throw std::logic_error("Error in Cholesky decomposition: matrix is not postive definite"); + LL[i][i] = sqrt(sum); + } + else + LL[j][i] = sum / LL[i][i]; + } + for (unsigned int k = i + 1; k < n; k++) + LL[i][k] = LL[k][i]; + } +} + +template +Matrix cholesky(const Matrix A) +{ + Matrix LL; + cholesky(A, LL); + + return LL; +} + +template +Vector cholesky_solve(const Matrix& LL, const Vector& b) +{ + if (LL.ncols() != LL.nrows()) + throw std::logic_error("Error in Cholesky solve: matrix must be squared"); + unsigned int n = LL.ncols(); + if (b.size() != n) + throw std::logic_error("Error in Cholesky decomposition: b vector must be of the same dimensions of LU matrix"); + Vector x, y; + + /* Solve L * y = b */ + forward_elimination(LL, y, b); + /* Solve L^T * x = y */ + backward_elimination(LL, x, y); + + return x; +} + +template +void cholesky_solve(const Matrix& LL, Vector& x, const Vector& b) +{ + x = cholesky_solve(LL, b); +} + +template +void forward_elimination(const Matrix& L, Vector& y, const Vector b) +{ + if (L.ncols() != L.nrows()) + throw std::logic_error("Error in Forward elimination: matrix must be squared (lower triangular)"); + if (b.size() != L.nrows()) + throw std::logic_error("Error in Forward elimination: b vector must be of the same dimensions of L matrix"); + unsigned int n = b.size(); + y.resize(n); + + y[0] = b[0] / L[0][0]; + for (unsigned int i = 1; i < n; i++) + { + y[i] = b[i]; + for (unsigned int j = 0; j < i; j++) + y[i] -= L[i][j] * y[j]; + y[i] = y[i] / L[i][i]; + } +} + +template +Vector forward_elimination(const Matrix& L, const Vector b) +{ + Vector y; + forward_elimination(L, y, b); + + return y; +} + +template +void backward_elimination(const Matrix& U, Vector& x, const Vector& y) +{ + if (U.ncols() != U.nrows()) + throw std::logic_error("Error in Backward elimination: matrix must be squared (upper triangular)"); + if (y.size() != U.nrows()) + throw std::logic_error("Error in Backward elimination: b vector must be of the same dimensions of U matrix"); + int n = y.size(); + x.resize(n); + + x[n - 1] = y[n - 1] / U[n - 1][n - 1]; + for (int i = n - 2; i >= 0; i--) + { + x[i] = y[i]; + for (int j = i + 1; j < n; j++) + x[i] -= U[i][j] * x[j]; + x[i] = x[i] / U[i][i]; + } +} + +template +Vector backward_elimination(const Matrix& U, const Vector y) +{ + Vector x; + forward_elimination(U, x, y); + + return x; +} + +/* Setting default linear systems machinery */ + +// #define det lu_det +// #define inverse lu_inverse +// #define solve lu_solve + +/* Random */ + +template +void random(Matrix& m) +{ + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + m[i][j] = (T)(rand() / double(RAND_MAX)); +} + +/** + Aggregate functions +*/ + +template +Vector sum(const Matrix& m) +{ + Vector tmp((T)0, m.ncols()); + for (unsigned int j = 0; j < m.ncols(); j++) + for (unsigned int i = 0; i < m.nrows(); i++) + tmp[j] += m[i][j]; + return tmp; +} + +template +Vector r_sum(const Matrix& m) +{ + Vector tmp((T)0, m.nrows()); + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp[i] += m[i][j]; + return tmp; +} + +template +T all_sum(const Matrix& m) +{ + T tmp = (T)0; + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp += m[i][j]; + return tmp; +} + +template +Vector prod(const Matrix& m) +{ + Vector tmp((T)1, m.ncols()); + for (unsigned int j = 0; j < m.ncols(); j++) + for (unsigned int i = 0; i < m.nrows(); i++) + tmp[j] *= m[i][j]; + return tmp; +} + +template +Vector r_prod(const Matrix& m) +{ + Vector tmp((T)1, m.nrows()); + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp[i] *= m[i][j]; + return tmp; +} + +template +T all_prod(const Matrix& m) +{ + T tmp = (T)1; + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp *= m[i][j]; + return tmp; +} + +template +Vector mean(const Matrix& m) +{ + Vector res((T)0, m.ncols()); + for (unsigned int j = 0; j < m.ncols(); j++) + { + for (unsigned int i = 0; i < m.nrows(); i++) + res[j] += m[i][j]; + res[j] /= m.nrows(); + } + + return res; +} + +template +Vector r_mean(const Matrix& m) +{ + Vector res((T)0, m.rows()); + for (unsigned int i = 0; i < m.nrows(); i++) + { + for (unsigned int j = 0; j < m.ncols(); j++) + res[i] += m[i][j]; + res[i] /= m.nrows(); + } + + return res; +} + +template +T all_mean(const Matrix& m) +{ + T tmp = (T)0; + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp += m[i][j]; + return tmp / (m.nrows() * m.ncols()); +} + +template +Vector var(const Matrix& m, bool sample_correction = false) +{ + Vector res((T)0, m.ncols()); + unsigned int n = m.nrows(); + double sum, ssum; + for (unsigned int j = 0; j < m.ncols(); j++) + { + sum = (T)0.0; ssum = (T)0.0; + for (unsigned int i = 0; i < m.nrows(); i++) + { + sum += m[i][j]; + ssum += (m[i][j] * m[i][j]); + } + if (!sample_correction) + res[j] = (ssum / n) - (sum / n) * (sum / n); + else + res[j] = n * ((ssum / n) - (sum / n) * (sum / n)) / (n - 1); + } + + return res; +} + +template +Vector stdev(const Matrix& m, bool sample_correction = false) +{ + return vec_sqrt(var(m, sample_correction)); +} + +template +Vector r_var(const Matrix& m, bool sample_correction = false) +{ + Vector res((T)0, m.nrows()); + double sum, ssum; + unsigned int n = m.ncols(); + for (unsigned int i = 0; i < m.nrows(); i++) + { + sum = 0.0; ssum = 0.0; + for (unsigned int j = 0; j < m.ncols(); j++) + { + sum += m[i][j]; + ssum += (m[i][j] * m[i][j]); + } + if (!sample_correction) + res[i] = (ssum / n) - (sum / n) * (sum / n); + else + res[i] = n * ((ssum / n) - (sum / n) * (sum / n)) / (n - 1); + } + + return res; +} + +template +Vector r_stdev(const Matrix& m, bool sample_correction = false) +{ + return vec_sqrt(r_var(m, sample_correction)); +} + +template +Vector max(const Matrix& m) +{ + Vector res(m.ncols()); + double value; + for (unsigned int j = 0; j < m.ncols(); j++) + { + value = m[0][j]; + for (unsigned int i = 1; i < m.nrows(); i++) + value = std::max(m[i][j], value); + res[j] = value; + } + + return res; +} + +template +Vector r_max(const Matrix& m) +{ + Vector res(m.nrows()); + double value; + for (unsigned int i = 0; i < m.nrows(); i++) + { + value = m[i][0]; + for (unsigned int j = 1; j < m.ncols(); j++) + value = std::max(m[i][j], value); + res[i] = value; + } + + return res; +} + +template +Vector min(const Matrix& m) +{ + Vector res(m.ncols()); + double value; + for (unsigned int j = 0; j < m.ncols(); j++) + { + value = m[0][j]; + for (unsigned int i = 1; i < m.nrows(); i++) + value = std::min(m[i][j], value); + res[j] = value; + } + + return res; +} + +template +Vector r_min(const Matrix& m) +{ + Vector res(m.nrows()); + double value; + for (unsigned int i = 0; i < m.nrows(); i++) + { + value = m[i][0]; + for (unsigned int j = 1; j < m.ncols(); j++) + value = std::min(m[i][j], value); + res[i] = value; + } + + return res; +} + + + +/** + Single element mathematical functions +*/ + +template +Matrix exp(const Matrix&m) +{ + Matrix tmp(m.nrows(), m.ncols()); + + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp[i][j] = exp(m[i][j]); + + return tmp; +} + +template +Matrix mat_sqrt(const Matrix&m) +{ + Matrix tmp(m.nrows(), m.ncols()); + + for (unsigned int i = 0; i < m.nrows(); i++) + for (unsigned int j = 0; j < m.ncols(); j++) + tmp[i][j] = sqrt(m[i][j]); + + return tmp; +} + +/** + Matrix operators +*/ + +template +Matrix kron(const Vector& b, const Vector& a) +{ + Matrix tmp(b.size(), a.size()); + for (unsigned int i = 0; i < b.size(); i++) + for (unsigned int j = 0; j < a.size(); j++) + tmp[i][j] = a[j] * b[i]; + + return tmp; +} + +template +Matrix t(const Matrix& a) +{ + Matrix tmp(a.ncols(), a.nrows()); + for (unsigned int i = 0; i < a.nrows(); i++) + for (unsigned int j = 0; j < a.ncols(); j++) + tmp[j][i] = a[i][j]; + + return tmp; +} + +template +Matrix dot_prod(const Matrix& a, const Matrix& b) +{ + if (a.ncols() != b.nrows()) + throw std::logic_error("Error matrix dot product: dimensions of the matrices are not compatible"); + Matrix tmp(a.nrows(), b.ncols()); + for (unsigned int i = 0; i < tmp.nrows(); i++) + for (unsigned int j = 0; j < tmp.ncols(); j++) + { + tmp[i][j] = (T)0; + for (unsigned int k = 0; k < a.ncols(); k++) + tmp[i][j] += a[i][k] * b[k][j]; + } + + return tmp; +} + +template +Matrix dot_prod(const Matrix& a, const Vector& b) +{ + if (a.ncols() != b.size()) + throw std::logic_error("Error matrix dot product: dimensions of the matrix and the vector are not compatible"); + Matrix tmp(a.nrows(), 1); + for (unsigned int i = 0; i < tmp.nrows(); i++) + { + tmp[i][0] = (T)0; + for (unsigned int k = 0; k < a.ncols(); k++) + tmp[i][0] += a[i][k] * b[k]; + } + + return tmp; +} + +template +Matrix dot_prod(const Vector& a, const Matrix& b) +{ + if (a.size() != b.nrows()) + throw std::logic_error("Error matrix dot product: dimensions of the vector and matrix are not compatible"); + Matrix tmp(1, b.ncols()); + for (unsigned int j = 0; j < tmp.ncols(); j++) + { + tmp[0][j] = (T)0; + for (unsigned int k = 0; k < a.size(); k++) + tmp[0][j] += a[k] * b[k][j]; + } + + return tmp; +} + +template +inline Matrix rank(const Matrix m) +{ + Matrix tmp(m.nrows(), m.ncols()); + for (unsigned int j = 0; j < m.ncols(); j++) + tmp.setColumn(j, rank(m.extractColumn(j))); + + return tmp; +} + +template +inline Matrix r_rank(const Matrix m) +{ + Matrix tmp(m.nrows(), m.ncols()); + for (unsigned int i = 0; i < m.nrows(); i++) + tmp.setRow(i, rank(m.extractRow(i))); + + return tmp; +} + +} // namespace quadprogpp + +#endif // define _ARRAY_HH_ diff --git a/include/thirdparty/quadProgpp/QuadProg++.hh b/include/thirdparty/quadProgpp/QuadProg++.hh old mode 100644 new mode 100755 index c2954d4..88660e1 --- a/include/thirdparty/quadProgpp/QuadProg++.hh +++ b/include/thirdparty/quadProgpp/QuadProg++.hh @@ -1,77 +1,77 @@ -/* - File $Id: QuadProg++.hh 232 2007-06-21 12:29:00Z digasper $ - - The quadprog_solve() function implements the algorithm of Goldfarb and Idnani - for the solution of a (convex) Quadratic Programming problem - by means of an active-set dual method. - -The problem is in the form: - -min 0.5 * x G x + g0 x -s.t. - CE^T x + ce0 = 0 - CI^T x + ci0 >= 0 - - The matrix and vectors dimensions are as follows: - G: n * n - g0: n - - CE: n * p - ce0: p - - CI: n * m - ci0: m - - x: n - - The function will return the cost of the solution written in the x vector or - std::numeric_limits::infinity() if the problem is infeasible. In the latter case - the value of the x vector is not correct. - - References: D. Goldfarb, A. Idnani. A numerically stable dual method for solving - strictly convex quadratic programs. Mathematical Programming 27 (1983) pp. 1-33. - - Notes: - 1. pay attention in setting up the vectors ce0 and ci0. - If the constraints of your problem are specified in the form - A^T x = b and C^T x >= d, then you should set ce0 = -b and ci0 = -d. - 2. The matrices have column dimension equal to MATRIX_DIM, - a constant set to 20 in this file (by means of a #define macro). - If the matrices are bigger than 20 x 20 the limit could be - increased by means of a -DMATRIX_DIM=n on the compiler command line. - 3. The matrix G is modified within the function since it is used to compute - the G = L^T L cholesky factorization for further computations inside the function. - If you need the original matrix G you should make a copy of it and pass the copy - to the function. - - Author: Luca Di Gaspero - DIEGM - University of Udine, Italy - luca.digaspero@uniud.it - http://www.diegm.uniud.it/digaspero/ - - The author will be grateful if the researchers using this software will - acknowledge the contribution of this function in their research papers. - - Copyright (c) 2007-2016 Luca Di Gaspero - - This software may be modified and distributed under the terms - of the MIT license. See the LICENSE file for details. -*/ - - -#ifndef _QUADPROGPP -#define _QUADPROGPP - -#include "thirdparty/quadProgpp/Array.hh" -#include - -namespace quadprogpp { - -double solve_quadprog(Matrix& G, Vector& g0, - const Matrix& CE, const Vector& ce0, - const Matrix& CI, const Vector& ci0, - Vector& x); - -} // namespace quadprogpp - -#endif // #define _QUADPROGPP +/* + File $Id: QuadProg++.hh 232 2007-06-21 12:29:00Z digasper $ + + The quadprog_solve() function implements the algorithm of Goldfarb and Idnani + for the solution of a (convex) Quadratic Programming problem + by means of an active-set dual method. + +The problem is in the form: + +min 0.5 * x G x + g0 x +s.t. + CE^T x + ce0 = 0 + CI^T x + ci0 >= 0 + + The matrix and vectors dimensions are as follows: + G: n * n + g0: n + + CE: n * p + ce0: p + + CI: n * m + ci0: m + + x: n + + The function will return the cost of the solution written in the x vector or + std::numeric_limits::infinity() if the problem is infeasible. In the latter case + the value of the x vector is not correct. + + References: D. Goldfarb, A. Idnani. A numerically stable dual method for solving + strictly convex quadratic programs. Mathematical Programming 27 (1983) pp. 1-33. + + Notes: + 1. pay attention in setting up the vectors ce0 and ci0. + If the constraints of your problem are specified in the form + A^T x = b and C^T x >= d, then you should set ce0 = -b and ci0 = -d. + 2. The matrices have column dimension equal to MATRIX_DIM, + a constant set to 20 in this file (by means of a #define macro). + If the matrices are bigger than 20 x 20 the limit could be + increased by means of a -DMATRIX_DIM=n on the compiler command line. + 3. The matrix G is modified within the function since it is used to compute + the G = L^T L cholesky factorization for further computations inside the function. + If you need the original matrix G you should make a copy of it and pass the copy + to the function. + + Author: Luca Di Gaspero + DIEGM - University of Udine, Italy + luca.digaspero@uniud.it + http://www.diegm.uniud.it/digaspero/ + + The author will be grateful if the researchers using this software will + acknowledge the contribution of this function in their research papers. + + Copyright (c) 2007-2016 Luca Di Gaspero + + This software may be modified and distributed under the terms + of the MIT license. See the LICENSE file for details. +*/ + + +#ifndef _QUADPROGPP +#define _QUADPROGPP + +#include "thirdparty/quadProgpp/Array.hh" +#include + +namespace quadprogpp { + +double solve_quadprog(Matrix& G, Vector& g0, + const Matrix& CE, const Vector& ce0, + const Matrix& CI, const Vector& ci0, + Vector& x); + +} // namespace quadprogpp + +#endif // #define _QUADPROGPP diff --git a/include/thirdparty/tinyxml/tinystr.h b/include/thirdparty/tinyxml/tinystr.h index 89cca33..c3cac34 100644 --- a/include/thirdparty/tinyxml/tinystr.h +++ b/include/thirdparty/tinyxml/tinystr.h @@ -1,305 +1,305 @@ -/* -www.sourceforge.net/projects/tinyxml - -This software is provided 'as-is', without any express or implied -warranty. In no event will the authors be held liable for any -damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must -not claim that you wrote the original software. If you use this -software in a product, an acknowledgment in the product documentation -would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and -must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source -distribution. -*/ - - -#ifndef TIXML_USE_STL - -#ifndef TIXML_STRING_INCLUDED -#define TIXML_STRING_INCLUDED - -#include -#include - -/* The support for explicit isn't that universal, and it isn't really - required - it is used to check that the TiXmlString class isn't incorrectly - used. Be nice to old compilers and macro it here: -*/ -#if defined(_MSC_VER) && (_MSC_VER >= 1200 ) - // Microsoft visual studio, version 6 and higher. - #define TIXML_EXPLICIT explicit -#elif defined(__GNUC__) && (__GNUC__ >= 3 ) - // GCC version 3 and higher.s - #define TIXML_EXPLICIT explicit -#else - #define TIXML_EXPLICIT -#endif - - -/* - TiXmlString is an emulation of a subset of the std::string template. - Its purpose is to allow compiling TinyXML on compilers with no or poor STL support. - Only the member functions relevant to the TinyXML project have been implemented. - The buffer allocation is made by a simplistic power of 2 like mechanism : if we increase - a string and there's no more room, we allocate a buffer twice as big as we need. -*/ -class TiXmlString -{ - public : - // The size type used - typedef size_t size_type; - - // Error value for find primitive - static const size_type npos; // = -1; - - - // TiXmlString empty constructor - TiXmlString () : rep_(&nullrep_) - { - } - - // TiXmlString copy constructor - TiXmlString ( const TiXmlString & copy) : rep_(0) - { - init(copy.length()); - memcpy(start(), copy.data(), length()); - } - - // TiXmlString constructor, based on a string - TIXML_EXPLICIT TiXmlString ( const char * copy) : rep_(0) - { - init( static_cast( strlen(copy) )); - memcpy(start(), copy, length()); - } - - // TiXmlString constructor, based on a string - TIXML_EXPLICIT TiXmlString ( const char * str, size_type len) : rep_(0) - { - init(len); - memcpy(start(), str, len); - } - - // TiXmlString destructor - ~TiXmlString () - { - quit(); - } - - TiXmlString& operator = (const char * copy) - { - return assign( copy, (size_type)strlen(copy)); - } - - TiXmlString& operator = (const TiXmlString & copy) - { - return assign(copy.start(), copy.length()); - } - - - // += operator. Maps to append - TiXmlString& operator += (const char * suffix) - { - return append(suffix, static_cast( strlen(suffix) )); - } - - // += operator. Maps to append - TiXmlString& operator += (char single) - { - return append(&single, 1); - } - - // += operator. Maps to append - TiXmlString& operator += (const TiXmlString & suffix) - { - return append(suffix.data(), suffix.length()); - } - - - // Convert a TiXmlString into a null-terminated char * - const char * c_str () const { return rep_->str; } - - // Convert a TiXmlString into a char * (need not be null terminated). - const char * data () const { return rep_->str; } - - // Return the length of a TiXmlString - size_type length () const { return rep_->size; } - - // Alias for length() - size_type size () const { return rep_->size; } - - // Checks if a TiXmlString is empty - bool empty () const { return rep_->size == 0; } - - // Return capacity of string - size_type capacity () const { return rep_->capacity; } - - - // single char extraction - const char& at (size_type index) const - { - assert( index < length() ); - return rep_->str[ index ]; - } - - // [] operator - char& operator [] (size_type index) const - { - assert( index < length() ); - return rep_->str[ index ]; - } - - // find a char in a string. Return TiXmlString::npos if not found - size_type find (char lookup) const - { - return find(lookup, 0); - } - - // find a char in a string from an offset. Return TiXmlString::npos if not found - size_type find (char tofind, size_type offset) const - { - if (offset >= length()) return npos; - - for (const char* p = c_str() + offset; *p != '\0'; ++p) - { - if (*p == tofind) return static_cast< size_type >( p - c_str() ); - } - return npos; - } - - void clear () - { - //Lee: - //The original was just too strange, though correct: - // TiXmlString().swap(*this); - //Instead use the quit & re-init: - quit(); - init(0,0); - } - - /* Function to reserve a big amount of data when we know we'll need it. Be aware that this - function DOES NOT clear the content of the TiXmlString if any exists. - */ - void reserve (size_type cap); - - TiXmlString& assign (const char* str, size_type len); - - TiXmlString& append (const char* str, size_type len); - - void swap (TiXmlString& other) - { - Rep* r = rep_; - rep_ = other.rep_; - other.rep_ = r; - } - - private: - - void init(size_type sz) { init(sz, sz); } - void set_size(size_type sz) { rep_->str[ rep_->size = sz ] = '\0'; } - char* start() const { return rep_->str; } - char* finish() const { return rep_->str + rep_->size; } - - struct Rep - { - size_type size, capacity; - char str[1]; - }; - - void init(size_type sz, size_type cap) - { - if (cap) - { - // Lee: the original form: - // rep_ = static_cast(operator new(sizeof(Rep) + cap)); - // doesn't work in some cases of new being overloaded. Switching - // to the normal allocation, although use an 'int' for systems - // that are overly picky about structure alignment. - const size_type bytesNeeded = sizeof(Rep) + cap; - const size_type intsNeeded = ( bytesNeeded + sizeof(int) - 1 ) / sizeof( int ); - rep_ = reinterpret_cast( new int[ intsNeeded ] ); - - rep_->str[ rep_->size = sz ] = '\0'; - rep_->capacity = cap; - } - else - { - rep_ = &nullrep_; - } - } - - void quit() - { - if (rep_ != &nullrep_) - { - // The rep_ is really an array of ints. (see the allocator, above). - // Cast it back before delete, so the compiler won't incorrectly call destructors. - delete [] ( reinterpret_cast( rep_ ) ); - } - } - - Rep * rep_; - static Rep nullrep_; - -} ; - - -inline bool operator == (const TiXmlString & a, const TiXmlString & b) -{ - return ( a.length() == b.length() ) // optimization on some platforms - && ( strcmp(a.c_str(), b.c_str()) == 0 ); // actual compare -} -inline bool operator < (const TiXmlString & a, const TiXmlString & b) -{ - return strcmp(a.c_str(), b.c_str()) < 0; -} - -inline bool operator != (const TiXmlString & a, const TiXmlString & b) { return !(a == b); } -inline bool operator > (const TiXmlString & a, const TiXmlString & b) { return b < a; } -inline bool operator <= (const TiXmlString & a, const TiXmlString & b) { return !(b < a); } -inline bool operator >= (const TiXmlString & a, const TiXmlString & b) { return !(a < b); } - -inline bool operator == (const TiXmlString & a, const char* b) { return strcmp(a.c_str(), b) == 0; } -inline bool operator == (const char* a, const TiXmlString & b) { return b == a; } -inline bool operator != (const TiXmlString & a, const char* b) { return !(a == b); } -inline bool operator != (const char* a, const TiXmlString & b) { return !(b == a); } - -TiXmlString operator + (const TiXmlString & a, const TiXmlString & b); -TiXmlString operator + (const TiXmlString & a, const char* b); -TiXmlString operator + (const char* a, const TiXmlString & b); - - -/* - TiXmlOutStream is an emulation of std::ostream. It is based on TiXmlString. - Only the operators that we need for TinyXML have been developped. -*/ -class TiXmlOutStream : public TiXmlString -{ -public : - - // TiXmlOutStream << operator. - TiXmlOutStream & operator << (const TiXmlString & in) - { - *this += in; - return *this; - } - - // TiXmlOutStream << operator. - TiXmlOutStream & operator << (const char * in) - { - *this += in; - return *this; - } - -} ; - -#endif // TIXML_STRING_INCLUDED -#endif // TIXML_USE_STL +/* +www.sourceforge.net/projects/tinyxml + +This software is provided 'as-is', without any express or implied +warranty. In no event will the authors be held liable for any +damages arising from the use of this software. + +Permission is granted to anyone to use this software for any +purpose, including commercial applications, and to alter it and +redistribute it freely, subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must +not claim that you wrote the original software. If you use this +software in a product, an acknowledgment in the product documentation +would be appreciated but is not required. + +2. Altered source versions must be plainly marked as such, and +must not be misrepresented as being the original software. + +3. This notice may not be removed or altered from any source +distribution. +*/ + + +#ifndef TIXML_USE_STL + +#ifndef TIXML_STRING_INCLUDED +#define TIXML_STRING_INCLUDED + +#include +#include + +/* The support for explicit isn't that universal, and it isn't really + required - it is used to check that the TiXmlString class isn't incorrectly + used. Be nice to old compilers and macro it here: +*/ +#if defined(_MSC_VER) && (_MSC_VER >= 1200 ) + // Microsoft visual studio, version 6 and higher. + #define TIXML_EXPLICIT explicit +#elif defined(__GNUC__) && (__GNUC__ >= 3 ) + // GCC version 3 and higher.s + #define TIXML_EXPLICIT explicit +#else + #define TIXML_EXPLICIT +#endif + + +/* + TiXmlString is an emulation of a subset of the std::string template. + Its purpose is to allow compiling TinyXML on compilers with no or poor STL support. + Only the member functions relevant to the TinyXML project have been implemented. + The buffer allocation is made by a simplistic power of 2 like mechanism : if we increase + a string and there's no more room, we allocate a buffer twice as big as we need. +*/ +class TiXmlString +{ + public : + // The size type used + typedef size_t size_type; + + // Error value for find primitive + static const size_type npos; // = -1; + + + // TiXmlString empty constructor + TiXmlString () : rep_(&nullrep_) + { + } + + // TiXmlString copy constructor + TiXmlString ( const TiXmlString & copy) : rep_(0) + { + init(copy.length()); + memcpy(start(), copy.data(), length()); + } + + // TiXmlString constructor, based on a string + TIXML_EXPLICIT TiXmlString ( const char * copy) : rep_(0) + { + init( static_cast( strlen(copy) )); + memcpy(start(), copy, length()); + } + + // TiXmlString constructor, based on a string + TIXML_EXPLICIT TiXmlString ( const char * str, size_type len) : rep_(0) + { + init(len); + memcpy(start(), str, len); + } + + // TiXmlString destructor + ~TiXmlString () + { + quit(); + } + + TiXmlString& operator = (const char * copy) + { + return assign( copy, (size_type)strlen(copy)); + } + + TiXmlString& operator = (const TiXmlString & copy) + { + return assign(copy.start(), copy.length()); + } + + + // += operator. Maps to append + TiXmlString& operator += (const char * suffix) + { + return append(suffix, static_cast( strlen(suffix) )); + } + + // += operator. Maps to append + TiXmlString& operator += (char single) + { + return append(&single, 1); + } + + // += operator. Maps to append + TiXmlString& operator += (const TiXmlString & suffix) + { + return append(suffix.data(), suffix.length()); + } + + + // Convert a TiXmlString into a null-terminated char * + const char * c_str () const { return rep_->str; } + + // Convert a TiXmlString into a char * (need not be null terminated). + const char * data () const { return rep_->str; } + + // Return the length of a TiXmlString + size_type length () const { return rep_->size; } + + // Alias for length() + size_type size () const { return rep_->size; } + + // Checks if a TiXmlString is empty + bool empty () const { return rep_->size == 0; } + + // Return capacity of string + size_type capacity () const { return rep_->capacity; } + + + // single char extraction + const char& at (size_type index) const + { + assert( index < length() ); + return rep_->str[ index ]; + } + + // [] operator + char& operator [] (size_type index) const + { + assert( index < length() ); + return rep_->str[ index ]; + } + + // find a char in a string. Return TiXmlString::npos if not found + size_type find (char lookup) const + { + return find(lookup, 0); + } + + // find a char in a string from an offset. Return TiXmlString::npos if not found + size_type find (char tofind, size_type offset) const + { + if (offset >= length()) return npos; + + for (const char* p = c_str() + offset; *p != '\0'; ++p) + { + if (*p == tofind) return static_cast< size_type >( p - c_str() ); + } + return npos; + } + + void clear () + { + //Lee: + //The original was just too strange, though correct: + // TiXmlString().swap(*this); + //Instead use the quit & re-init: + quit(); + init(0,0); + } + + /* Function to reserve a big amount of data when we know we'll need it. Be aware that this + function DOES NOT clear the content of the TiXmlString if any exists. + */ + void reserve (size_type cap); + + TiXmlString& assign (const char* str, size_type len); + + TiXmlString& append (const char* str, size_type len); + + void swap (TiXmlString& other) + { + Rep* r = rep_; + rep_ = other.rep_; + other.rep_ = r; + } + + private: + + void init(size_type sz) { init(sz, sz); } + void set_size(size_type sz) { rep_->str[ rep_->size = sz ] = '\0'; } + char* start() const { return rep_->str; } + char* finish() const { return rep_->str + rep_->size; } + + struct Rep + { + size_type size, capacity; + char str[1]; + }; + + void init(size_type sz, size_type cap) + { + if (cap) + { + // Lee: the original form: + // rep_ = static_cast(operator new(sizeof(Rep) + cap)); + // doesn't work in some cases of new being overloaded. Switching + // to the normal allocation, although use an 'int' for systems + // that are overly picky about structure alignment. + const size_type bytesNeeded = sizeof(Rep) + cap; + const size_type intsNeeded = ( bytesNeeded + sizeof(int) - 1 ) / sizeof( int ); + rep_ = reinterpret_cast( new int[ intsNeeded ] ); + + rep_->str[ rep_->size = sz ] = '\0'; + rep_->capacity = cap; + } + else + { + rep_ = &nullrep_; + } + } + + void quit() + { + if (rep_ != &nullrep_) + { + // The rep_ is really an array of ints. (see the allocator, above). + // Cast it back before delete, so the compiler won't incorrectly call destructors. + delete [] ( reinterpret_cast( rep_ ) ); + } + } + + Rep * rep_; + static Rep nullrep_; + +} ; + + +inline bool operator == (const TiXmlString & a, const TiXmlString & b) +{ + return ( a.length() == b.length() ) // optimization on some platforms + && ( strcmp(a.c_str(), b.c_str()) == 0 ); // actual compare +} +inline bool operator < (const TiXmlString & a, const TiXmlString & b) +{ + return strcmp(a.c_str(), b.c_str()) < 0; +} + +inline bool operator != (const TiXmlString & a, const TiXmlString & b) { return !(a == b); } +inline bool operator > (const TiXmlString & a, const TiXmlString & b) { return b < a; } +inline bool operator <= (const TiXmlString & a, const TiXmlString & b) { return !(b < a); } +inline bool operator >= (const TiXmlString & a, const TiXmlString & b) { return !(a < b); } + +inline bool operator == (const TiXmlString & a, const char* b) { return strcmp(a.c_str(), b) == 0; } +inline bool operator == (const char* a, const TiXmlString & b) { return b == a; } +inline bool operator != (const TiXmlString & a, const char* b) { return !(a == b); } +inline bool operator != (const char* a, const TiXmlString & b) { return !(b == a); } + +TiXmlString operator + (const TiXmlString & a, const TiXmlString & b); +TiXmlString operator + (const TiXmlString & a, const char* b); +TiXmlString operator + (const char* a, const TiXmlString & b); + + +/* + TiXmlOutStream is an emulation of std::ostream. It is based on TiXmlString. + Only the operators that we need for TinyXML have been developped. +*/ +class TiXmlOutStream : public TiXmlString +{ +public : + + // TiXmlOutStream << operator. + TiXmlOutStream & operator << (const TiXmlString & in) + { + *this += in; + return *this; + } + + // TiXmlOutStream << operator. + TiXmlOutStream & operator << (const char * in) + { + *this += in; + return *this; + } + +} ; + +#endif // TIXML_STRING_INCLUDED +#endif // TIXML_USE_STL diff --git a/include/thirdparty/tinyxml/tinyxml.h b/include/thirdparty/tinyxml/tinyxml.h index a3589e5..d051548 100644 --- a/include/thirdparty/tinyxml/tinyxml.h +++ b/include/thirdparty/tinyxml/tinyxml.h @@ -1,1805 +1,1805 @@ -/* -www.sourceforge.net/projects/tinyxml -Original code by Lee Thomason (www.grinninglizard.com) - -This software is provided 'as-is', without any express or implied -warranty. In no event will the authors be held liable for any -damages arising from the use of this software. - -Permission is granted to anyone to use this software for any -purpose, including commercial applications, and to alter it and -redistribute it freely, subject to the following restrictions: - -1. The origin of this software must not be misrepresented; you must -not claim that you wrote the original software. If you use this -software in a product, an acknowledgment in the product documentation -would be appreciated but is not required. - -2. Altered source versions must be plainly marked as such, and -must not be misrepresented as being the original software. - -3. This notice may not be removed or altered from any source -distribution. -*/ - - -#ifndef TINYXML_INCLUDED -#define TINYXML_INCLUDED - -#ifdef _MSC_VER -#pragma warning( push ) -#pragma warning( disable : 4530 ) -#pragma warning( disable : 4786 ) -#endif - -#include -#include -#include -#include -#include - -// Help out windows: -#if defined( _DEBUG ) && !defined( DEBUG ) -#define DEBUG -#endif - -#ifdef TIXML_USE_STL - #include - #include - #include - #define TIXML_STRING std::string -#else - #include "tinystr.h" - #define TIXML_STRING TiXmlString -#endif - -// Deprecated library function hell. Compilers want to use the -// new safe versions. This probably doesn't fully address the problem, -// but it gets closer. There are too many compilers for me to fully -// test. If you get compilation troubles, undefine TIXML_SAFE -#define TIXML_SAFE - -#ifdef TIXML_SAFE - #if defined(_MSC_VER) && (_MSC_VER >= 1400 ) - // Microsoft visual studio, version 2005 and higher. - #define TIXML_SNPRINTF _snprintf_s - #define TIXML_SSCANF sscanf_s - #elif defined(_MSC_VER) && (_MSC_VER >= 1200 ) - // Microsoft visual studio, version 6 and higher. - //#pragma message( "Using _sn* functions." ) - #define TIXML_SNPRINTF _snprintf - #define TIXML_SSCANF sscanf - #elif defined(__GNUC__) && (__GNUC__ >= 3 ) - // GCC version 3 and higher.s - //#warning( "Using sn* functions." ) - #define TIXML_SNPRINTF snprintf - #define TIXML_SSCANF sscanf - #else - #define TIXML_SNPRINTF snprintf - #define TIXML_SSCANF sscanf - #endif -#endif - -class TiXmlDocument; -class TiXmlElement; -class TiXmlComment; -class TiXmlUnknown; -class TiXmlAttribute; -class TiXmlText; -class TiXmlDeclaration; -class TiXmlParsingData; - -const int TIXML_MAJOR_VERSION = 2; -const int TIXML_MINOR_VERSION = 6; -const int TIXML_PATCH_VERSION = 2; - -/* Internal structure for tracking location of items - in the XML file. -*/ -struct TiXmlCursor -{ - TiXmlCursor() { Clear(); } - void Clear() { row = col = -1; } - - int row; // 0 based. - int col; // 0 based. -}; - - -/** - Implements the interface to the "Visitor pattern" (see the Accept() method.) - If you call the Accept() method, it requires being passed a TiXmlVisitor - class to handle callbacks. For nodes that contain other nodes (Document, Element) - you will get called with a VisitEnter/VisitExit pair. Nodes that are always leaves - are simply called with Visit(). - - If you return 'true' from a Visit method, recursive parsing will continue. If you return - false, no children of this node or its sibilings will be Visited. - - All flavors of Visit methods have a default implementation that returns 'true' (continue - visiting). You need to only override methods that are interesting to you. - - Generally Accept() is called on the TiXmlDocument, although all nodes suppert Visiting. - - You should never change the document from a callback. - - @sa TiXmlNode::Accept() -*/ -class TiXmlVisitor -{ -public: - virtual ~TiXmlVisitor() {} - - /// Visit a document. - virtual bool VisitEnter( const TiXmlDocument& /*doc*/ ) { return true; } - /// Visit a document. - virtual bool VisitExit( const TiXmlDocument& /*doc*/ ) { return true; } - - /// Visit an element. - virtual bool VisitEnter( const TiXmlElement& /*element*/, const TiXmlAttribute* /*firstAttribute*/ ) { return true; } - /// Visit an element. - virtual bool VisitExit( const TiXmlElement& /*element*/ ) { return true; } - - /// Visit a declaration - virtual bool Visit( const TiXmlDeclaration& /*declaration*/ ) { return true; } - /// Visit a text node - virtual bool Visit( const TiXmlText& /*text*/ ) { return true; } - /// Visit a comment node - virtual bool Visit( const TiXmlComment& /*comment*/ ) { return true; } - /// Visit an unknown node - virtual bool Visit( const TiXmlUnknown& /*unknown*/ ) { return true; } -}; - -// Only used by Attribute::Query functions -enum -{ - TIXML_SUCCESS, - TIXML_NO_ATTRIBUTE, - TIXML_WRONG_TYPE -}; - - -// Used by the parsing routines. -enum TiXmlEncoding -{ - TIXML_ENCODING_UNKNOWN, - TIXML_ENCODING_UTF8, - TIXML_ENCODING_LEGACY -}; - -const TiXmlEncoding TIXML_DEFAULT_ENCODING = TIXML_ENCODING_UNKNOWN; - -/** TiXmlBase is a base class for every class in TinyXml. - It does little except to establish that TinyXml classes - can be printed and provide some utility functions. - - In XML, the document and elements can contain - other elements and other types of nodes. - - @verbatim - A Document can contain: Element (container or leaf) - Comment (leaf) - Unknown (leaf) - Declaration( leaf ) - - An Element can contain: Element (container or leaf) - Text (leaf) - Attributes (not on tree) - Comment (leaf) - Unknown (leaf) - - A Decleration contains: Attributes (not on tree) - @endverbatim -*/ -class TiXmlBase -{ - friend class TiXmlNode; - friend class TiXmlElement; - friend class TiXmlDocument; - -public: - TiXmlBase() : userData(0) {} - virtual ~TiXmlBase() {} - - /** All TinyXml classes can print themselves to a filestream - or the string class (TiXmlString in non-STL mode, std::string - in STL mode.) Either or both cfile and str can be null. - - This is a formatted print, and will insert - tabs and newlines. - - (For an unformatted stream, use the << operator.) - */ - virtual void Print( FILE* cfile, int depth ) const = 0; - - /** The world does not agree on whether white space should be kept or - not. In order to make everyone happy, these global, static functions - are provided to set whether or not TinyXml will condense all white space - into a single space or not. The default is to condense. Note changing this - value is not thread safe. - */ - static void SetCondenseWhiteSpace( bool condense ) { condenseWhiteSpace = condense; } - - /// Return the current white space setting. - static bool IsWhiteSpaceCondensed() { return condenseWhiteSpace; } - - /** Return the position, in the original source file, of this node or attribute. - The row and column are 1-based. (That is the first row and first column is - 1,1). If the returns values are 0 or less, then the parser does not have - a row and column value. - - Generally, the row and column value will be set when the TiXmlDocument::Load(), - TiXmlDocument::LoadFile(), or any TiXmlNode::Parse() is called. It will NOT be set - when the DOM was created from operator>>. - - The values reflect the initial load. Once the DOM is modified programmatically - (by adding or changing nodes and attributes) the new values will NOT update to - reflect changes in the document. - - There is a minor performance cost to computing the row and column. Computation - can be disabled if TiXmlDocument::SetTabSize() is called with 0 as the value. - - @sa TiXmlDocument::SetTabSize() - */ - int Row() const { return location.row + 1; } - int Column() const { return location.col + 1; } ///< See Row() - - void SetUserData( void* user ) { userData = user; } ///< Set a pointer to arbitrary user data. - void* GetUserData() { return userData; } ///< Get a pointer to arbitrary user data. - const void* GetUserData() const { return userData; } ///< Get a pointer to arbitrary user data. - - // Table that returs, for a given lead byte, the total number of bytes - // in the UTF-8 sequence. - static const int utf8ByteTable[256]; - - virtual const char* Parse( const char* p, - TiXmlParsingData* data, - TiXmlEncoding encoding /*= TIXML_ENCODING_UNKNOWN */ ) = 0; - - /** Expands entities in a string. Note this should not contian the tag's '<', '>', etc, - or they will be transformed into entities! - */ - static void EncodeString( const TIXML_STRING& str, TIXML_STRING* out ); - - enum - { - TIXML_NO_ERROR = 0, - TIXML_ERROR, - TIXML_ERROR_OPENING_FILE, - TIXML_ERROR_PARSING_ELEMENT, - TIXML_ERROR_FAILED_TO_READ_ELEMENT_NAME, - TIXML_ERROR_READING_ELEMENT_VALUE, - TIXML_ERROR_READING_ATTRIBUTES, - TIXML_ERROR_PARSING_EMPTY, - TIXML_ERROR_READING_END_TAG, - TIXML_ERROR_PARSING_UNKNOWN, - TIXML_ERROR_PARSING_COMMENT, - TIXML_ERROR_PARSING_DECLARATION, - TIXML_ERROR_DOCUMENT_EMPTY, - TIXML_ERROR_EMBEDDED_NULL, - TIXML_ERROR_PARSING_CDATA, - TIXML_ERROR_DOCUMENT_TOP_ONLY, - - TIXML_ERROR_STRING_COUNT - }; - -protected: - - static const char* SkipWhiteSpace( const char*, TiXmlEncoding encoding ); - - inline static bool IsWhiteSpace( char c ) - { - return ( isspace( (unsigned char) c ) || c == '\n' || c == '\r' ); - } - inline static bool IsWhiteSpace( int c ) - { - if ( c < 256 ) - return IsWhiteSpace( (char) c ); - return false; // Again, only truly correct for English/Latin...but usually works. - } - - #ifdef TIXML_USE_STL - static bool StreamWhiteSpace( std::istream * in, TIXML_STRING * tag ); - static bool StreamTo( std::istream * in, int character, TIXML_STRING * tag ); - #endif - - /* Reads an XML name into the string provided. Returns - a pointer just past the last character of the name, - or 0 if the function has an error. - */ - static const char* ReadName( const char* p, TIXML_STRING* name, TiXmlEncoding encoding ); - - /* Reads text. Returns a pointer past the given end tag. - Wickedly complex options, but it keeps the (sensitive) code in one place. - */ - static const char* ReadText( const char* in, // where to start - TIXML_STRING* text, // the string read - bool ignoreWhiteSpace, // whether to keep the white space - const char* endTag, // what ends this text - bool ignoreCase, // whether to ignore case in the end tag - TiXmlEncoding encoding ); // the current encoding - - // If an entity has been found, transform it into a character. - static const char* GetEntity( const char* in, char* value, int* length, TiXmlEncoding encoding ); - - // Get a character, while interpreting entities. - // The length can be from 0 to 4 bytes. - inline static const char* GetChar( const char* p, char* _value, int* length, TiXmlEncoding encoding ) - { - assert( p ); - if ( encoding == TIXML_ENCODING_UTF8 ) - { - *length = utf8ByteTable[ *((const unsigned char*)p) ]; - assert( *length >= 0 && *length < 5 ); - } - else - { - *length = 1; - } - - if ( *length == 1 ) - { - if ( *p == '&' ) - return GetEntity( p, _value, length, encoding ); - *_value = *p; - return p+1; - } - else if ( *length ) - { - //strncpy( _value, p, *length ); // lots of compilers don't like this function (unsafe), - // and the null terminator isn't needed - for( int i=0; p[i] && i<*length; ++i ) { - _value[i] = p[i]; - } - return p + (*length); - } - else - { - // Not valid text. - return 0; - } - } - - // Return true if the next characters in the stream are any of the endTag sequences. - // Ignore case only works for english, and should only be relied on when comparing - // to English words: StringEqual( p, "version", true ) is fine. - static bool StringEqual( const char* p, - const char* endTag, - bool ignoreCase, - TiXmlEncoding encoding ); - - static const char* errorString[ TIXML_ERROR_STRING_COUNT ]; - - TiXmlCursor location; - - /// Field containing a generic user pointer - void* userData; - - // None of these methods are reliable for any language except English. - // Good for approximation, not great for accuracy. - static int IsAlpha( unsigned char anyByte, TiXmlEncoding encoding ); - static int IsAlphaNum( unsigned char anyByte, TiXmlEncoding encoding ); - inline static int ToLower( int v, TiXmlEncoding encoding ) - { - if ( encoding == TIXML_ENCODING_UTF8 ) - { - if ( v < 128 ) return tolower( v ); - return v; - } - else - { - return tolower( v ); - } - } - static void ConvertUTF32ToUTF8( unsigned long input, char* output, int* length ); - -private: - TiXmlBase( const TiXmlBase& ); // not implemented. - void operator=( const TiXmlBase& base ); // not allowed. - - struct Entity - { - const char* str; - unsigned int strLength; - char chr; - }; - enum - { - NUM_ENTITY = 5, - MAX_ENTITY_LENGTH = 6 - - }; - static Entity entity[ NUM_ENTITY ]; - static bool condenseWhiteSpace; -}; - - -/** The parent class for everything in the Document Object Model. - (Except for attributes). - Nodes have siblings, a parent, and children. A node can be - in a document, or stand on its own. The type of a TiXmlNode - can be queried, and it can be cast to its more defined type. -*/ -class TiXmlNode : public TiXmlBase -{ - friend class TiXmlDocument; - friend class TiXmlElement; - -public: - #ifdef TIXML_USE_STL - - /** An input stream operator, for every class. Tolerant of newlines and - formatting, but doesn't expect them. - */ - friend std::istream& operator >> (std::istream& in, TiXmlNode& base); - - /** An output stream operator, for every class. Note that this outputs - without any newlines or formatting, as opposed to Print(), which - includes tabs and new lines. - - The operator<< and operator>> are not completely symmetric. Writing - a node to a stream is very well defined. You'll get a nice stream - of output, without any extra whitespace or newlines. - - But reading is not as well defined. (As it always is.) If you create - a TiXmlElement (for example) and read that from an input stream, - the text needs to define an element or junk will result. This is - true of all input streams, but it's worth keeping in mind. - - A TiXmlDocument will read nodes until it reads a root element, and - all the children of that root element. - */ - friend std::ostream& operator<< (std::ostream& out, const TiXmlNode& base); - - /// Appends the XML node or attribute to a std::string. - friend std::string& operator<< (std::string& out, const TiXmlNode& base ); - - #endif - - /** The types of XML nodes supported by TinyXml. (All the - unsupported types are picked up by UNKNOWN.) - */ - enum NodeType - { - TINYXML_DOCUMENT, - TINYXML_ELEMENT, - TINYXML_COMMENT, - TINYXML_UNKNOWN, - TINYXML_TEXT, - TINYXML_DECLARATION, - TINYXML_TYPECOUNT - }; - - virtual ~TiXmlNode(); - - /** The meaning of 'value' changes for the specific type of - TiXmlNode. - @verbatim - Document: filename of the xml file - Element: name of the element - Comment: the comment text - Unknown: the tag contents - Text: the text string - @endverbatim - - The subclasses will wrap this function. - */ - const char *Value() const { return value.c_str (); } - - #ifdef TIXML_USE_STL - /** Return Value() as a std::string. If you only use STL, - this is more efficient than calling Value(). - Only available in STL mode. - */ - const std::string& ValueStr() const { return value; } - #endif - - const TIXML_STRING& ValueTStr() const { return value; } - - /** Changes the value of the node. Defined as: - @verbatim - Document: filename of the xml file - Element: name of the element - Comment: the comment text - Unknown: the tag contents - Text: the text string - @endverbatim - */ - void SetValue(const char * _value) { value = _value;} - - #ifdef TIXML_USE_STL - /// STL std::string form. - void SetValue( const std::string& _value ) { value = _value; } - #endif - - /// Delete all the children of this node. Does not affect 'this'. - void Clear(); - - /// One step up the DOM. - TiXmlNode* Parent() { return parent; } - const TiXmlNode* Parent() const { return parent; } - - const TiXmlNode* FirstChild() const { return firstChild; } ///< The first child of this node. Will be null if there are no children. - TiXmlNode* FirstChild() { return firstChild; } - const TiXmlNode* FirstChild( const char * value ) const; ///< The first child of this node with the matching 'value'. Will be null if none found. - /// The first child of this node with the matching 'value'. Will be null if none found. - TiXmlNode* FirstChild( const char * _value ) { - // Call through to the const version - safe since nothing is changed. Exiting syntax: cast this to a const (always safe) - // call the method, cast the return back to non-const. - return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->FirstChild( _value )); - } - const TiXmlNode* LastChild() const { return lastChild; } /// The last child of this node. Will be null if there are no children. - TiXmlNode* LastChild() { return lastChild; } - - const TiXmlNode* LastChild( const char * value ) const; /// The last child of this node matching 'value'. Will be null if there are no children. - TiXmlNode* LastChild( const char * _value ) { - return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->LastChild( _value )); - } - - #ifdef TIXML_USE_STL - const TiXmlNode* FirstChild( const std::string& _value ) const { return FirstChild (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* FirstChild( const std::string& _value ) { return FirstChild (_value.c_str ()); } ///< STL std::string form. - const TiXmlNode* LastChild( const std::string& _value ) const { return LastChild (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* LastChild( const std::string& _value ) { return LastChild (_value.c_str ()); } ///< STL std::string form. - #endif - - /** An alternate way to walk the children of a node. - One way to iterate over nodes is: - @verbatim - for( child = parent->FirstChild(); child; child = child->NextSibling() ) - @endverbatim - - IterateChildren does the same thing with the syntax: - @verbatim - child = 0; - while( child = parent->IterateChildren( child ) ) - @endverbatim - - IterateChildren takes the previous child as input and finds - the next one. If the previous child is null, it returns the - first. IterateChildren will return null when done. - */ - const TiXmlNode* IterateChildren( const TiXmlNode* previous ) const; - TiXmlNode* IterateChildren( const TiXmlNode* previous ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( previous ) ); - } - - /// This flavor of IterateChildren searches for children with a particular 'value' - const TiXmlNode* IterateChildren( const char * value, const TiXmlNode* previous ) const; - TiXmlNode* IterateChildren( const char * _value, const TiXmlNode* previous ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( _value, previous ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) const { return IterateChildren (_value.c_str (), previous); } ///< STL std::string form. - TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) { return IterateChildren (_value.c_str (), previous); } ///< STL std::string form. - #endif - - /** Add a new node related to this. Adds a child past the LastChild. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* InsertEndChild( const TiXmlNode& addThis ); - - - /** Add a new node related to this. Adds a child past the LastChild. - - NOTE: the node to be added is passed by pointer, and will be - henceforth owned (and deleted) by tinyXml. This method is efficient - and avoids an extra copy, but should be used with care as it - uses a different memory model than the other insert functions. - - @sa InsertEndChild - */ - TiXmlNode* LinkEndChild( TiXmlNode* addThis ); - - /** Add a new node related to this. Adds a child before the specified child. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* InsertBeforeChild( TiXmlNode* beforeThis, const TiXmlNode& addThis ); - - /** Add a new node related to this. Adds a child after the specified child. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* InsertAfterChild( TiXmlNode* afterThis, const TiXmlNode& addThis ); - - /** Replace a child of this node. - Returns a pointer to the new object or NULL if an error occured. - */ - TiXmlNode* ReplaceChild( TiXmlNode* replaceThis, const TiXmlNode& withThis ); - - /// Delete a child of this node. - bool RemoveChild( TiXmlNode* removeThis ); - - /// Navigate to a sibling node. - const TiXmlNode* PreviousSibling() const { return prev; } - TiXmlNode* PreviousSibling() { return prev; } - - /// Navigate to a sibling node. - const TiXmlNode* PreviousSibling( const char * ) const; - TiXmlNode* PreviousSibling( const char *_prev ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->PreviousSibling( _prev ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlNode* PreviousSibling( const std::string& _value ) const { return PreviousSibling (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* PreviousSibling( const std::string& _value ) { return PreviousSibling (_value.c_str ()); } ///< STL std::string form. - const TiXmlNode* NextSibling( const std::string& _value) const { return NextSibling (_value.c_str ()); } ///< STL std::string form. - TiXmlNode* NextSibling( const std::string& _value) { return NextSibling (_value.c_str ()); } ///< STL std::string form. - #endif - - /// Navigate to a sibling node. - const TiXmlNode* NextSibling() const { return next; } - TiXmlNode* NextSibling() { return next; } - - /// Navigate to a sibling node with the given 'value'. - const TiXmlNode* NextSibling( const char * ) const; - TiXmlNode* NextSibling( const char* _next ) { - return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->NextSibling( _next ) ); - } - - /** Convenience function to get through elements. - Calls NextSibling and ToElement. Will skip all non-Element - nodes. Returns 0 if there is not another element. - */ - const TiXmlElement* NextSiblingElement() const; - TiXmlElement* NextSiblingElement() { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement() ); - } - - /** Convenience function to get through elements. - Calls NextSibling and ToElement. Will skip all non-Element - nodes. Returns 0 if there is not another element. - */ - const TiXmlElement* NextSiblingElement( const char * ) const; - TiXmlElement* NextSiblingElement( const char *_next ) { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement( _next ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlElement* NextSiblingElement( const std::string& _value) const { return NextSiblingElement (_value.c_str ()); } ///< STL std::string form. - TiXmlElement* NextSiblingElement( const std::string& _value) { return NextSiblingElement (_value.c_str ()); } ///< STL std::string form. - #endif - - /// Convenience function to get through elements. - const TiXmlElement* FirstChildElement() const; - TiXmlElement* FirstChildElement() { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement() ); - } - - /// Convenience function to get through elements. - const TiXmlElement* FirstChildElement( const char * _value ) const; - TiXmlElement* FirstChildElement( const char * _value ) { - return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement( _value ) ); - } - - #ifdef TIXML_USE_STL - const TiXmlElement* FirstChildElement( const std::string& _value ) const { return FirstChildElement (_value.c_str ()); } ///< STL std::string form. - TiXmlElement* FirstChildElement( const std::string& _value ) { return FirstChildElement (_value.c_str ()); } ///< STL std::string form. - #endif - - /** Query the type (as an enumerated value, above) of this node. - The possible types are: TINYXML_DOCUMENT, TINYXML_ELEMENT, TINYXML_COMMENT, - TINYXML_UNKNOWN, TINYXML_TEXT, and TINYXML_DECLARATION. - */ - int Type() const { return type; } - - /** Return a pointer to the Document this node lives in. - Returns null if not in a document. - */ - const TiXmlDocument* GetDocument() const; - TiXmlDocument* GetDocument() { - return const_cast< TiXmlDocument* >( (const_cast< const TiXmlNode* >(this))->GetDocument() ); - } - - /// Returns true if this node has no children. - bool NoChildren() const { return !firstChild; } - - virtual const TiXmlDocument* ToDocument() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlElement* ToElement() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlComment* ToComment() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlUnknown* ToUnknown() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlText* ToText() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual const TiXmlDeclaration* ToDeclaration() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - - virtual TiXmlDocument* ToDocument() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlElement* ToElement() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlComment* ToComment() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlUnknown* ToUnknown() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlText* ToText() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - virtual TiXmlDeclaration* ToDeclaration() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. - - /** Create an exact duplicate of this node and return it. The memory must be deleted - by the caller. - */ - virtual TiXmlNode* Clone() const = 0; - - /** Accept a hierchical visit the nodes in the TinyXML DOM. Every node in the - XML tree will be conditionally visited and the host will be called back - via the TiXmlVisitor interface. - - This is essentially a SAX interface for TinyXML. (Note however it doesn't re-parse - the XML for the callbacks, so the performance of TinyXML is unchanged by using this - interface versus any other.) - - The interface has been based on ideas from: - - - http://www.saxproject.org/ - - http://c2.com/cgi/wiki?HierarchicalVisitorPattern - - Which are both good references for "visiting". - - An example of using Accept(): - @verbatim - TiXmlPrinter printer; - tinyxmlDoc.Accept( &printer ); - const char* xmlcstr = printer.CStr(); - @endverbatim - */ - virtual bool Accept( TiXmlVisitor* visitor ) const = 0; - -protected: - TiXmlNode( NodeType _type ); - - // Copy to the allocated object. Shared functionality between Clone, Copy constructor, - // and the assignment operator. - void CopyTo( TiXmlNode* target ) const; - - #ifdef TIXML_USE_STL - // The real work of the input operator. - virtual void StreamIn( std::istream* in, TIXML_STRING* tag ) = 0; - #endif - - // Figure out what is at *p, and parse it. Returns null if it is not an xml node. - TiXmlNode* Identify( const char* start, TiXmlEncoding encoding ); - - TiXmlNode* parent; - NodeType type; - - TiXmlNode* firstChild; - TiXmlNode* lastChild; - - TIXML_STRING value; - - TiXmlNode* prev; - TiXmlNode* next; - -private: - TiXmlNode( const TiXmlNode& ); // not implemented. - void operator=( const TiXmlNode& base ); // not allowed. -}; - - -/** An attribute is a name-value pair. Elements have an arbitrary - number of attributes, each with a unique name. - - @note The attributes are not TiXmlNodes, since they are not - part of the tinyXML document object model. There are other - suggested ways to look at this problem. -*/ -class TiXmlAttribute : public TiXmlBase -{ - friend class TiXmlAttributeSet; - -public: - /// Construct an empty attribute. - TiXmlAttribute() : TiXmlBase() - { - document = 0; - prev = next = 0; - } - - #ifdef TIXML_USE_STL - /// std::string constructor. - TiXmlAttribute( const std::string& _name, const std::string& _value ) - { - name = _name; - value = _value; - document = 0; - prev = next = 0; - } - #endif - - /// Construct an attribute with a name and value. - TiXmlAttribute( const char * _name, const char * _value ) - { - name = _name; - value = _value; - document = 0; - prev = next = 0; - } - - const char* Name() const { return name.c_str(); } ///< Return the name of this attribute. - const char* Value() const { return value.c_str(); } ///< Return the value of this attribute. - #ifdef TIXML_USE_STL - const std::string& ValueStr() const { return value; } ///< Return the value of this attribute. - #endif - int IntValue() const; ///< Return the value of this attribute, converted to an integer. - double DoubleValue() const; ///< Return the value of this attribute, converted to a double. - - // Get the tinyxml string representation - const TIXML_STRING& NameTStr() const { return name; } - - /** QueryIntValue examines the value string. It is an alternative to the - IntValue() method with richer error checking. - If the value is an integer, it is stored in 'value' and - the call returns TIXML_SUCCESS. If it is not - an integer, it returns TIXML_WRONG_TYPE. - - A specialized but useful call. Note that for success it returns 0, - which is the opposite of almost all other TinyXml calls. - */ - int QueryIntValue( int* _value ) const; - /// QueryDoubleValue examines the value string. See QueryIntValue(). - int QueryDoubleValue( double* _value ) const; - - void SetName( const char* _name ) { name = _name; } ///< Set the name of this attribute. - void SetValue( const char* _value ) { value = _value; } ///< Set the value. - - void SetIntValue( int _value ); ///< Set the value from an integer. - void SetDoubleValue( double _value ); ///< Set the value from a double. - - #ifdef TIXML_USE_STL - /// STL std::string form. - void SetName( const std::string& _name ) { name = _name; } - /// STL std::string form. - void SetValue( const std::string& _value ) { value = _value; } - #endif - - /// Get the next sibling attribute in the DOM. Returns null at end. - const TiXmlAttribute* Next() const; - TiXmlAttribute* Next() { - return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Next() ); - } - - /// Get the previous sibling attribute in the DOM. Returns null at beginning. - const TiXmlAttribute* Previous() const; - TiXmlAttribute* Previous() { - return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Previous() ); - } - - bool operator==( const TiXmlAttribute& rhs ) const { return rhs.name == name; } - bool operator<( const TiXmlAttribute& rhs ) const { return name < rhs.name; } - bool operator>( const TiXmlAttribute& rhs ) const { return name > rhs.name; } - - /* Attribute parsing starts: first letter of the name - returns: the next char after the value end quote - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - // Prints this Attribute to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const { - Print( cfile, depth, 0 ); - } - void Print( FILE* cfile, int depth, TIXML_STRING* str ) const; - - // [internal use] - // Set the document pointer so the attribute can report errors. - void SetDocument( TiXmlDocument* doc ) { document = doc; } - -private: - TiXmlAttribute( const TiXmlAttribute& ); // not implemented. - void operator=( const TiXmlAttribute& base ); // not allowed. - - TiXmlDocument* document; // A pointer back to a document, for error reporting. - TIXML_STRING name; - TIXML_STRING value; - TiXmlAttribute* prev; - TiXmlAttribute* next; -}; - - -/* A class used to manage a group of attributes. - It is only used internally, both by the ELEMENT and the DECLARATION. - - The set can be changed transparent to the Element and Declaration - classes that use it, but NOT transparent to the Attribute - which has to implement a next() and previous() method. Which makes - it a bit problematic and prevents the use of STL. - - This version is implemented with circular lists because: - - I like circular lists - - it demonstrates some independence from the (typical) doubly linked list. -*/ -class TiXmlAttributeSet -{ -public: - TiXmlAttributeSet(); - ~TiXmlAttributeSet(); - - void Add( TiXmlAttribute* attribute ); - void Remove( TiXmlAttribute* attribute ); - - const TiXmlAttribute* First() const { return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; } - TiXmlAttribute* First() { return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; } - const TiXmlAttribute* Last() const { return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; } - TiXmlAttribute* Last() { return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; } - - TiXmlAttribute* Find( const char* _name ) const; - TiXmlAttribute* FindOrCreate( const char* _name ); - -# ifdef TIXML_USE_STL - TiXmlAttribute* Find( const std::string& _name ) const; - TiXmlAttribute* FindOrCreate( const std::string& _name ); -# endif - - -private: - //*ME: Because of hidden/disabled copy-construktor in TiXmlAttribute (sentinel-element), - //*ME: this class must be also use a hidden/disabled copy-constructor !!! - TiXmlAttributeSet( const TiXmlAttributeSet& ); // not allowed - void operator=( const TiXmlAttributeSet& ); // not allowed (as TiXmlAttribute) - - TiXmlAttribute sentinel; -}; - - -/** The element is a container class. It has a value, the element name, - and can contain other elements, text, comments, and unknowns. - Elements also contain an arbitrary number of attributes. -*/ -class TiXmlElement : public TiXmlNode -{ -public: - /// Construct an element. - TiXmlElement (const char * in_value); - - #ifdef TIXML_USE_STL - /// std::string constructor. - TiXmlElement( const std::string& _value ); - #endif - - TiXmlElement( const TiXmlElement& ); - - TiXmlElement& operator=( const TiXmlElement& base ); - - virtual ~TiXmlElement(); - - /** Given an attribute name, Attribute() returns the value - for the attribute of that name, or null if none exists. - */ - const char* Attribute( const char* name ) const; - - /** Given an attribute name, Attribute() returns the value - for the attribute of that name, or null if none exists. - If the attribute exists and can be converted to an integer, - the integer value will be put in the return 'i', if 'i' - is non-null. - */ - const char* Attribute( const char* name, int* i ) const; - - /** Given an attribute name, Attribute() returns the value - for the attribute of that name, or null if none exists. - If the attribute exists and can be converted to an double, - the double value will be put in the return 'd', if 'd' - is non-null. - */ - const char* Attribute( const char* name, double* d ) const; - - /** QueryIntAttribute examines the attribute - it is an alternative to the - Attribute() method with richer error checking. - If the attribute is an integer, it is stored in 'value' and - the call returns TIXML_SUCCESS. If it is not - an integer, it returns TIXML_WRONG_TYPE. If the attribute - does not exist, then TIXML_NO_ATTRIBUTE is returned. - */ - int QueryIntAttribute( const char* name, int* _value ) const; - /// QueryUnsignedAttribute examines the attribute - see QueryIntAttribute(). - int QueryUnsignedAttribute( const char* name, unsigned* _value ) const; - /** QueryBoolAttribute examines the attribute - see QueryIntAttribute(). - Note that '1', 'true', or 'yes' are considered true, while '0', 'false' - and 'no' are considered false. - */ - int QueryBoolAttribute( const char* name, bool* _value ) const; - /// QueryDoubleAttribute examines the attribute - see QueryIntAttribute(). - int QueryDoubleAttribute( const char* name, double* _value ) const; - /// QueryFloatAttribute examines the attribute - see QueryIntAttribute(). - int QueryFloatAttribute( const char* name, float* _value ) const { - double d; - int result = QueryDoubleAttribute( name, &d ); - if ( result == TIXML_SUCCESS ) { - *_value = (float)d; - } - return result; - } - - #ifdef TIXML_USE_STL - /// QueryStringAttribute examines the attribute - see QueryIntAttribute(). - int QueryStringAttribute( const char* name, std::string* _value ) const { - const char* cstr = Attribute( name ); - if ( cstr ) { - *_value = std::string( cstr ); - return TIXML_SUCCESS; - } - return TIXML_NO_ATTRIBUTE; - } - - /** Template form of the attribute query which will try to read the - attribute into the specified type. Very easy, very powerful, but - be careful to make sure to call this with the correct type. - - NOTE: This method doesn't work correctly for 'string' types that contain spaces. - - @return TIXML_SUCCESS, TIXML_WRONG_TYPE, or TIXML_NO_ATTRIBUTE - */ - template< typename T > int QueryValueAttribute( const std::string& name, T* outValue ) const - { - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( !node ) - return TIXML_NO_ATTRIBUTE; - - std::stringstream sstream( node->ValueStr() ); - sstream >> *outValue; - if ( !sstream.fail() ) - return TIXML_SUCCESS; - return TIXML_WRONG_TYPE; - } - - int QueryValueAttribute( const std::string& name, std::string* outValue ) const - { - const TiXmlAttribute* node = attributeSet.Find( name ); - if ( !node ) - return TIXML_NO_ATTRIBUTE; - *outValue = node->ValueStr(); - return TIXML_SUCCESS; - } - #endif - - /** Sets an attribute of name to a given value. The attribute - will be created if it does not exist, or changed if it does. - */ - void SetAttribute( const char* name, const char * _value ); - - #ifdef TIXML_USE_STL - const std::string* Attribute( const std::string& name ) const; - const std::string* Attribute( const std::string& name, int* i ) const; - const std::string* Attribute( const std::string& name, double* d ) const; - int QueryIntAttribute( const std::string& name, int* _value ) const; - int QueryDoubleAttribute( const std::string& name, double* _value ) const; - - /// STL std::string form. - void SetAttribute( const std::string& name, const std::string& _value ); - ///< STL std::string form. - void SetAttribute( const std::string& name, int _value ); - ///< STL std::string form. - void SetDoubleAttribute( const std::string& name, double value ); - #endif - - /** Sets an attribute of name to a given value. The attribute - will be created if it does not exist, or changed if it does. - */ - void SetAttribute( const char * name, int value ); - - /** Sets an attribute of name to a given value. The attribute - will be created if it does not exist, or changed if it does. - */ - void SetDoubleAttribute( const char * name, double value ); - - /** Deletes an attribute with the given name. - */ - void RemoveAttribute( const char * name ); - #ifdef TIXML_USE_STL - void RemoveAttribute( const std::string& name ) { RemoveAttribute (name.c_str ()); } ///< STL std::string form. - #endif - - const TiXmlAttribute* FirstAttribute() const { return attributeSet.First(); } ///< Access the first attribute in this element. - TiXmlAttribute* FirstAttribute() { return attributeSet.First(); } - const TiXmlAttribute* LastAttribute() const { return attributeSet.Last(); } ///< Access the last attribute in this element. - TiXmlAttribute* LastAttribute() { return attributeSet.Last(); } - - /** Convenience function for easy access to the text inside an element. Although easy - and concise, GetText() is limited compared to getting the TiXmlText child - and accessing it directly. - - If the first child of 'this' is a TiXmlText, the GetText() - returns the character string of the Text node, else null is returned. - - This is a convenient method for getting the text of simple contained text: - @verbatim - This is text - const char* str = fooElement->GetText(); - @endverbatim - - 'str' will be a pointer to "This is text". - - Note that this function can be misleading. If the element foo was created from - this XML: - @verbatim - This is text - @endverbatim - - then the value of str would be null. The first child node isn't a text node, it is - another element. From this XML: - @verbatim - This is text - @endverbatim - GetText() will return "This is ". - - WARNING: GetText() accesses a child node - don't become confused with the - similarly named TiXmlHandle::Text() and TiXmlNode::ToText() which are - safe type casts on the referenced node. - */ - const char* GetText() const; - - /// Creates a new Element and returns it - the returned element is a copy. - virtual TiXmlNode* Clone() const; - // Print the Element to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - /* Attribtue parsing starts: next char past '<' - returns: next char past '>' - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlElement* ToElement() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlElement* ToElement() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* visitor ) const; - -protected: - - void CopyTo( TiXmlElement* target ) const; - void ClearThis(); // like clear, but initializes 'this' object as well - - // Used to be public [internal use] - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - /* [internal use] - Reads the "value" of the element -- another element, or text. - This should terminate with the current end tag. - */ - const char* ReadValue( const char* in, TiXmlParsingData* prevData, TiXmlEncoding encoding ); - -private: - TiXmlAttributeSet attributeSet; -}; - - -/** An XML comment. -*/ -class TiXmlComment : public TiXmlNode -{ -public: - /// Constructs an empty comment. - TiXmlComment() : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) {} - /// Construct a comment from text. - TiXmlComment( const char* _value ) : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) { - SetValue( _value ); - } - TiXmlComment( const TiXmlComment& ); - TiXmlComment& operator=( const TiXmlComment& base ); - - virtual ~TiXmlComment() {} - - /// Returns a copy of this Comment. - virtual TiXmlNode* Clone() const; - // Write this Comment to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - /* Attribtue parsing starts: at the ! of the !-- - returns: next char past '>' - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlComment* ToComment() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlComment* ToComment() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* visitor ) const; - -protected: - void CopyTo( TiXmlComment* target ) const; - - // used to be public - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif -// virtual void StreamOut( TIXML_OSTREAM * out ) const; - -private: - -}; - - -/** XML text. A text node can have 2 ways to output the next. "normal" output - and CDATA. It will default to the mode it was parsed from the XML file and - you generally want to leave it alone, but you can change the output mode with - SetCDATA() and query it with CDATA(). -*/ -class TiXmlText : public TiXmlNode -{ - friend class TiXmlElement; -public: - /** Constructor for text element. By default, it is treated as - normal, encoded text. If you want it be output as a CDATA text - element, set the parameter _cdata to 'true' - */ - TiXmlText (const char * initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT) - { - SetValue( initValue ); - cdata = false; - } - virtual ~TiXmlText() {} - - #ifdef TIXML_USE_STL - /// Constructor. - TiXmlText( const std::string& initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT) - { - SetValue( initValue ); - cdata = false; - } - #endif - - TiXmlText( const TiXmlText& copy ) : TiXmlNode( TiXmlNode::TINYXML_TEXT ) { copy.CopyTo( this ); } - TiXmlText& operator=( const TiXmlText& base ) { base.CopyTo( this ); return *this; } - - // Write this text object to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - /// Queries whether this represents text using a CDATA section. - bool CDATA() const { return cdata; } - /// Turns on or off a CDATA representation of text. - void SetCDATA( bool _cdata ) { cdata = _cdata; } - - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlText* ToText() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlText* ToText() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* content ) const; - -protected : - /// [internal use] Creates a new Element and returns it. - virtual TiXmlNode* Clone() const; - void CopyTo( TiXmlText* target ) const; - - bool Blank() const; // returns true if all white space and new lines - // [internal use] - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - bool cdata; // true if this should be input and output as a CDATA style text element -}; - - -/** In correct XML the declaration is the first entry in the file. - @verbatim - - @endverbatim - - TinyXml will happily read or write files without a declaration, - however. There are 3 possible attributes to the declaration: - version, encoding, and standalone. - - Note: In this version of the code, the attributes are - handled as special cases, not generic attributes, simply - because there can only be at most 3 and they are always the same. -*/ -class TiXmlDeclaration : public TiXmlNode -{ -public: - /// Construct an empty declaration. - TiXmlDeclaration() : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) {} - -#ifdef TIXML_USE_STL - /// Constructor. - TiXmlDeclaration( const std::string& _version, - const std::string& _encoding, - const std::string& _standalone ); -#endif - - /// Construct. - TiXmlDeclaration( const char* _version, - const char* _encoding, - const char* _standalone ); - - TiXmlDeclaration( const TiXmlDeclaration& copy ); - TiXmlDeclaration& operator=( const TiXmlDeclaration& copy ); - - virtual ~TiXmlDeclaration() {} - - /// Version. Will return an empty string if none was found. - const char *Version() const { return version.c_str (); } - /// Encoding. Will return an empty string if none was found. - const char *Encoding() const { return encoding.c_str (); } - /// Is this a standalone document? - const char *Standalone() const { return standalone.c_str (); } - - /// Creates a copy of this Declaration and returns it. - virtual TiXmlNode* Clone() const; - // Print this declaration to a FILE stream. - virtual void Print( FILE* cfile, int depth, TIXML_STRING* str ) const; - virtual void Print( FILE* cfile, int depth ) const { - Print( cfile, depth, 0 ); - } - - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlDeclaration* ToDeclaration() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlDeclaration* ToDeclaration() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* visitor ) const; - -protected: - void CopyTo( TiXmlDeclaration* target ) const; - // used to be public - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - - TIXML_STRING version; - TIXML_STRING encoding; - TIXML_STRING standalone; -}; - - -/** Any tag that tinyXml doesn't recognize is saved as an - unknown. It is a tag of text, but should not be modified. - It will be written back to the XML, unchanged, when the file - is saved. - - DTD tags get thrown into TiXmlUnknowns. -*/ -class TiXmlUnknown : public TiXmlNode -{ -public: - TiXmlUnknown() : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN ) {} - virtual ~TiXmlUnknown() {} - - TiXmlUnknown( const TiXmlUnknown& copy ) : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN ) { copy.CopyTo( this ); } - TiXmlUnknown& operator=( const TiXmlUnknown& copy ) { copy.CopyTo( this ); return *this; } - - /// Creates a copy of this Unknown and returns it. - virtual TiXmlNode* Clone() const; - // Print this Unknown to a FILE stream. - virtual void Print( FILE* cfile, int depth ) const; - - virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); - - virtual const TiXmlUnknown* ToUnknown() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlUnknown* ToUnknown() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* content ) const; - -protected: - void CopyTo( TiXmlUnknown* target ) const; - - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - -}; - - -/** Always the top level node. A document binds together all the - XML pieces. It can be saved, loaded, and printed to the screen. - The 'value' of a document node is the xml file name. -*/ -class TiXmlDocument : public TiXmlNode -{ -public: - /// Create an empty document, that has no name. - TiXmlDocument(); - /// Create a document with a name. The name of the document is also the filename of the xml. - TiXmlDocument( const char * documentName ); - - #ifdef TIXML_USE_STL - /// Constructor. - TiXmlDocument( const std::string& documentName ); - #endif - - TiXmlDocument( const TiXmlDocument& copy ); - TiXmlDocument& operator=( const TiXmlDocument& copy ); - - virtual ~TiXmlDocument() {} - - /** Load a file using the current document value. - Returns true if successful. Will delete any existing - document data before loading. - */ - bool LoadFile( TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - /// Save a file using the current document value. Returns true if successful. - bool SaveFile() const; - /// Load a file using the given filename. Returns true if successful. - bool LoadFile( const char * filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - /// Save a file using the given filename. Returns true if successful. - bool SaveFile( const char * filename ) const; - /** Load a file using the given FILE*. Returns true if successful. Note that this method - doesn't stream - the entire object pointed at by the FILE* - will be interpreted as an XML file. TinyXML doesn't stream in XML from the current - file location. Streaming may be added in the future. - */ - bool LoadFile( FILE*, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - /// Save a file using the given FILE*. Returns true if successful. - bool SaveFile( FILE* ) const; - - #ifdef TIXML_USE_STL - bool LoadFile( const std::string& filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ) ///< STL std::string version. - { - return LoadFile( filename.c_str(), encoding ); - } - bool SaveFile( const std::string& filename ) const ///< STL std::string version. - { - return SaveFile( filename.c_str() ); - } - #endif - - /** Parse the given null terminated block of xml data. Passing in an encoding to this - method (either TIXML_ENCODING_LEGACY or TIXML_ENCODING_UTF8 will force TinyXml - to use that encoding, regardless of what TinyXml might otherwise try to detect. - */ - virtual const char* Parse( const char* p, TiXmlParsingData* data = 0, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); - - /** Get the root element -- the only top level element -- of the document. - In well formed XML, there should only be one. TinyXml is tolerant of - multiple elements at the document level. - */ - const TiXmlElement* RootElement() const { return FirstChildElement(); } - TiXmlElement* RootElement() { return FirstChildElement(); } - - /** If an error occurs, Error will be set to true. Also, - - The ErrorId() will contain the integer identifier of the error (not generally useful) - - The ErrorDesc() method will return the name of the error. (very useful) - - The ErrorRow() and ErrorCol() will return the location of the error (if known) - */ - bool Error() const { return error; } - - /// Contains a textual (english) description of the error if one occurs. - const char * ErrorDesc() const { return errorDesc.c_str (); } - - /** Generally, you probably want the error string ( ErrorDesc() ). But if you - prefer the ErrorId, this function will fetch it. - */ - int ErrorId() const { return errorId; } - - /** Returns the location (if known) of the error. The first column is column 1, - and the first row is row 1. A value of 0 means the row and column wasn't applicable - (memory errors, for example, have no row/column) or the parser lost the error. (An - error in the error reporting, in that case.) - - @sa SetTabSize, Row, Column - */ - int ErrorRow() const { return errorLocation.row+1; } - int ErrorCol() const { return errorLocation.col+1; } ///< The column where the error occured. See ErrorRow() - - /** SetTabSize() allows the error reporting functions (ErrorRow() and ErrorCol()) - to report the correct values for row and column. It does not change the output - or input in any way. - - By calling this method, with a tab size - greater than 0, the row and column of each node and attribute is stored - when the file is loaded. Very useful for tracking the DOM back in to - the source file. - - The tab size is required for calculating the location of nodes. If not - set, the default of 4 is used. The tabsize is set per document. Setting - the tabsize to 0 disables row/column tracking. - - Note that row and column tracking is not supported when using operator>>. - - The tab size needs to be enabled before the parse or load. Correct usage: - @verbatim - TiXmlDocument doc; - doc.SetTabSize( 8 ); - doc.Load( "myfile.xml" ); - @endverbatim - - @sa Row, Column - */ - void SetTabSize( int _tabsize ) { tabsize = _tabsize; } - - int TabSize() const { return tabsize; } - - /** If you have handled the error, it can be reset with this call. The error - state is automatically cleared if you Parse a new XML block. - */ - void ClearError() { error = false; - errorId = 0; - errorDesc = ""; - errorLocation.row = errorLocation.col = 0; - //errorLocation.last = 0; - } - - /** Write the document to standard out using formatted printing ("pretty print"). */ - void Print() const { Print( stdout, 0 ); } - - /* Write the document to a string using formatted printing ("pretty print"). This - will allocate a character array (new char[]) and return it as a pointer. The - calling code pust call delete[] on the return char* to avoid a memory leak. - */ - //char* PrintToMemory() const; - - /// Print this Document to a FILE stream. - virtual void Print( FILE* cfile, int depth = 0 ) const; - // [internal use] - void SetError( int err, const char* errorLocation, TiXmlParsingData* prevData, TiXmlEncoding encoding ); - - virtual const TiXmlDocument* ToDocument() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - virtual TiXmlDocument* ToDocument() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. - - /** Walk the XML tree visiting this node and all of its children. - */ - virtual bool Accept( TiXmlVisitor* content ) const; - -protected : - // [internal use] - virtual TiXmlNode* Clone() const; - #ifdef TIXML_USE_STL - virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); - #endif - -private: - void CopyTo( TiXmlDocument* target ) const; - - bool error; - int errorId; - TIXML_STRING errorDesc; - int tabsize; - TiXmlCursor errorLocation; - bool useMicrosoftBOM; // the UTF-8 BOM were found when read. Note this, and try to write. -}; - - -/** - A TiXmlHandle is a class that wraps a node pointer with null checks; this is - an incredibly useful thing. Note that TiXmlHandle is not part of the TinyXml - DOM structure. It is a separate utility class. - - Take an example: - @verbatim - - - - - - - @endverbatim - - Assuming you want the value of "attributeB" in the 2nd "Child" element, it's very - easy to write a *lot* of code that looks like: - - @verbatim - TiXmlElement* root = document.FirstChildElement( "Document" ); - if ( root ) - { - TiXmlElement* element = root->FirstChildElement( "Element" ); - if ( element ) - { - TiXmlElement* child = element->FirstChildElement( "Child" ); - if ( child ) - { - TiXmlElement* child2 = child->NextSiblingElement( "Child" ); - if ( child2 ) - { - // Finally do something useful. - @endverbatim - - And that doesn't even cover "else" cases. TiXmlHandle addresses the verbosity - of such code. A TiXmlHandle checks for null pointers so it is perfectly safe - and correct to use: - - @verbatim - TiXmlHandle docHandle( &document ); - TiXmlElement* child2 = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", 1 ).ToElement(); - if ( child2 ) - { - // do something useful - @endverbatim - - Which is MUCH more concise and useful. - - It is also safe to copy handles - internally they are nothing more than node pointers. - @verbatim - TiXmlHandle handleCopy = handle; - @endverbatim - - What they should not be used for is iteration: - - @verbatim - int i=0; - while ( true ) - { - TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", i ).ToElement(); - if ( !child ) - break; - // do something - ++i; - } - @endverbatim - - It seems reasonable, but it is in fact two embedded while loops. The Child method is - a linear walk to find the element, so this code would iterate much more than it needs - to. Instead, prefer: - - @verbatim - TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).FirstChild( "Child" ).ToElement(); - - for( child; child; child=child->NextSiblingElement() ) - { - // do something - } - @endverbatim -*/ -class TiXmlHandle -{ -public: - /// Create a handle from any node (at any depth of the tree.) This can be a null pointer. - TiXmlHandle( TiXmlNode* _node ) { this->node = _node; } - /// Copy constructor - TiXmlHandle( const TiXmlHandle& ref ) { this->node = ref.node; } - TiXmlHandle operator=( const TiXmlHandle& ref ) { if ( &ref != this ) this->node = ref.node; return *this; } - - /// Return a handle to the first child node. - TiXmlHandle FirstChild() const; - /// Return a handle to the first child node with the given name. - TiXmlHandle FirstChild( const char * value ) const; - /// Return a handle to the first child element. - TiXmlHandle FirstChildElement() const; - /// Return a handle to the first child element with the given name. - TiXmlHandle FirstChildElement( const char * value ) const; - - /** Return a handle to the "index" child with the given name. - The first child is 0, the second 1, etc. - */ - TiXmlHandle Child( const char* value, int index ) const; - /** Return a handle to the "index" child. - The first child is 0, the second 1, etc. - */ - TiXmlHandle Child( int index ) const; - /** Return a handle to the "index" child element with the given name. - The first child element is 0, the second 1, etc. Note that only TiXmlElements - are indexed: other types are not counted. - */ - TiXmlHandle ChildElement( const char* value, int index ) const; - /** Return a handle to the "index" child element. - The first child element is 0, the second 1, etc. Note that only TiXmlElements - are indexed: other types are not counted. - */ - TiXmlHandle ChildElement( int index ) const; - - #ifdef TIXML_USE_STL - TiXmlHandle FirstChild( const std::string& _value ) const { return FirstChild( _value.c_str() ); } - TiXmlHandle FirstChildElement( const std::string& _value ) const { return FirstChildElement( _value.c_str() ); } - - TiXmlHandle Child( const std::string& _value, int index ) const { return Child( _value.c_str(), index ); } - TiXmlHandle ChildElement( const std::string& _value, int index ) const { return ChildElement( _value.c_str(), index ); } - #endif - - /** Return the handle as a TiXmlNode. This may return null. - */ - TiXmlNode* ToNode() const { return node; } - /** Return the handle as a TiXmlElement. This may return null. - */ - TiXmlElement* ToElement() const { return ( ( node && node->ToElement() ) ? node->ToElement() : 0 ); } - /** Return the handle as a TiXmlText. This may return null. - */ - TiXmlText* ToText() const { return ( ( node && node->ToText() ) ? node->ToText() : 0 ); } - /** Return the handle as a TiXmlUnknown. This may return null. - */ - TiXmlUnknown* ToUnknown() const { return ( ( node && node->ToUnknown() ) ? node->ToUnknown() : 0 ); } - - /** @deprecated use ToNode. - Return the handle as a TiXmlNode. This may return null. - */ - TiXmlNode* Node() const { return ToNode(); } - /** @deprecated use ToElement. - Return the handle as a TiXmlElement. This may return null. - */ - TiXmlElement* Element() const { return ToElement(); } - /** @deprecated use ToText() - Return the handle as a TiXmlText. This may return null. - */ - TiXmlText* Text() const { return ToText(); } - /** @deprecated use ToUnknown() - Return the handle as a TiXmlUnknown. This may return null. - */ - TiXmlUnknown* Unknown() const { return ToUnknown(); } - -private: - TiXmlNode* node; -}; - - -/** Print to memory functionality. The TiXmlPrinter is useful when you need to: - - -# Print to memory (especially in non-STL mode) - -# Control formatting (line endings, etc.) - - When constructed, the TiXmlPrinter is in its default "pretty printing" mode. - Before calling Accept() you can call methods to control the printing - of the XML document. After TiXmlNode::Accept() is called, the printed document can - be accessed via the CStr(), Str(), and Size() methods. - - TiXmlPrinter uses the Visitor API. - @verbatim - TiXmlPrinter printer; - printer.SetIndent( "\t" ); - - doc.Accept( &printer ); - fprintf( stdout, "%s", printer.CStr() ); - @endverbatim -*/ -class TiXmlPrinter : public TiXmlVisitor -{ -public: - TiXmlPrinter() : depth( 0 ), simpleTextPrint( false ), - buffer(), indent( " " ), lineBreak( "\n" ) {} - - virtual bool VisitEnter( const TiXmlDocument& doc ); - virtual bool VisitExit( const TiXmlDocument& doc ); - - virtual bool VisitEnter( const TiXmlElement& element, const TiXmlAttribute* firstAttribute ); - virtual bool VisitExit( const TiXmlElement& element ); - - virtual bool Visit( const TiXmlDeclaration& declaration ); - virtual bool Visit( const TiXmlText& text ); - virtual bool Visit( const TiXmlComment& comment ); - virtual bool Visit( const TiXmlUnknown& unknown ); - - /** Set the indent characters for printing. By default 4 spaces - but tab (\t) is also useful, or null/empty string for no indentation. - */ - void SetIndent( const char* _indent ) { indent = _indent ? _indent : "" ; } - /// Query the indention string. - const char* Indent() { return indent.c_str(); } - /** Set the line breaking string. By default set to newline (\n). - Some operating systems prefer other characters, or can be - set to the null/empty string for no indenation. - */ - void SetLineBreak( const char* _lineBreak ) { lineBreak = _lineBreak ? _lineBreak : ""; } - /// Query the current line breaking string. - const char* LineBreak() { return lineBreak.c_str(); } - - /** Switch over to "stream printing" which is the most dense formatting without - linebreaks. Common when the XML is needed for network transmission. - */ - void SetStreamPrinting() { indent = ""; - lineBreak = ""; - } - /// Return the result. - const char* CStr() { return buffer.c_str(); } - /// Return the length of the result string. - size_t Size() { return buffer.size(); } - - #ifdef TIXML_USE_STL - /// Return the result. - const std::string& Str() { return buffer; } - #endif - -private: - void DoIndent() { - for( int i=0; i +#include +#include +#include +#include + +// Help out windows: +#if defined( _DEBUG ) && !defined( DEBUG ) +#define DEBUG +#endif + +#ifdef TIXML_USE_STL + #include + #include + #include + #define TIXML_STRING std::string +#else + #include "tinystr.h" + #define TIXML_STRING TiXmlString +#endif + +// Deprecated library function hell. Compilers want to use the +// new safe versions. This probably doesn't fully address the problem, +// but it gets closer. There are too many compilers for me to fully +// test. If you get compilation troubles, undefine TIXML_SAFE +#define TIXML_SAFE + +#ifdef TIXML_SAFE + #if defined(_MSC_VER) && (_MSC_VER >= 1400 ) + // Microsoft visual studio, version 2005 and higher. + #define TIXML_SNPRINTF _snprintf_s + #define TIXML_SSCANF sscanf_s + #elif defined(_MSC_VER) && (_MSC_VER >= 1200 ) + // Microsoft visual studio, version 6 and higher. + //#pragma message( "Using _sn* functions." ) + #define TIXML_SNPRINTF _snprintf + #define TIXML_SSCANF sscanf + #elif defined(__GNUC__) && (__GNUC__ >= 3 ) + // GCC version 3 and higher.s + //#warning( "Using sn* functions." ) + #define TIXML_SNPRINTF snprintf + #define TIXML_SSCANF sscanf + #else + #define TIXML_SNPRINTF snprintf + #define TIXML_SSCANF sscanf + #endif +#endif + +class TiXmlDocument; +class TiXmlElement; +class TiXmlComment; +class TiXmlUnknown; +class TiXmlAttribute; +class TiXmlText; +class TiXmlDeclaration; +class TiXmlParsingData; + +const int TIXML_MAJOR_VERSION = 2; +const int TIXML_MINOR_VERSION = 6; +const int TIXML_PATCH_VERSION = 2; + +/* Internal structure for tracking location of items + in the XML file. +*/ +struct TiXmlCursor +{ + TiXmlCursor() { Clear(); } + void Clear() { row = col = -1; } + + int row; // 0 based. + int col; // 0 based. +}; + + +/** + Implements the interface to the "Visitor pattern" (see the Accept() method.) + If you call the Accept() method, it requires being passed a TiXmlVisitor + class to handle callbacks. For nodes that contain other nodes (Document, Element) + you will get called with a VisitEnter/VisitExit pair. Nodes that are always leaves + are simply called with Visit(). + + If you return 'true' from a Visit method, recursive parsing will continue. If you return + false, no children of this node or its sibilings will be Visited. + + All flavors of Visit methods have a default implementation that returns 'true' (continue + visiting). You need to only override methods that are interesting to you. + + Generally Accept() is called on the TiXmlDocument, although all nodes suppert Visiting. + + You should never change the document from a callback. + + @sa TiXmlNode::Accept() +*/ +class TiXmlVisitor +{ +public: + virtual ~TiXmlVisitor() {} + + /// Visit a document. + virtual bool VisitEnter( const TiXmlDocument& /*doc*/ ) { return true; } + /// Visit a document. + virtual bool VisitExit( const TiXmlDocument& /*doc*/ ) { return true; } + + /// Visit an element. + virtual bool VisitEnter( const TiXmlElement& /*element*/, const TiXmlAttribute* /*firstAttribute*/ ) { return true; } + /// Visit an element. + virtual bool VisitExit( const TiXmlElement& /*element*/ ) { return true; } + + /// Visit a declaration + virtual bool Visit( const TiXmlDeclaration& /*declaration*/ ) { return true; } + /// Visit a text node + virtual bool Visit( const TiXmlText& /*text*/ ) { return true; } + /// Visit a comment node + virtual bool Visit( const TiXmlComment& /*comment*/ ) { return true; } + /// Visit an unknown node + virtual bool Visit( const TiXmlUnknown& /*unknown*/ ) { return true; } +}; + +// Only used by Attribute::Query functions +enum +{ + TIXML_SUCCESS, + TIXML_NO_ATTRIBUTE, + TIXML_WRONG_TYPE +}; + + +// Used by the parsing routines. +enum TiXmlEncoding +{ + TIXML_ENCODING_UNKNOWN, + TIXML_ENCODING_UTF8, + TIXML_ENCODING_LEGACY +}; + +const TiXmlEncoding TIXML_DEFAULT_ENCODING = TIXML_ENCODING_UNKNOWN; + +/** TiXmlBase is a base class for every class in TinyXml. + It does little except to establish that TinyXml classes + can be printed and provide some utility functions. + + In XML, the document and elements can contain + other elements and other types of nodes. + + @verbatim + A Document can contain: Element (container or leaf) + Comment (leaf) + Unknown (leaf) + Declaration( leaf ) + + An Element can contain: Element (container or leaf) + Text (leaf) + Attributes (not on tree) + Comment (leaf) + Unknown (leaf) + + A Decleration contains: Attributes (not on tree) + @endverbatim +*/ +class TiXmlBase +{ + friend class TiXmlNode; + friend class TiXmlElement; + friend class TiXmlDocument; + +public: + TiXmlBase() : userData(0) {} + virtual ~TiXmlBase() {} + + /** All TinyXml classes can print themselves to a filestream + or the string class (TiXmlString in non-STL mode, std::string + in STL mode.) Either or both cfile and str can be null. + + This is a formatted print, and will insert + tabs and newlines. + + (For an unformatted stream, use the << operator.) + */ + virtual void Print( FILE* cfile, int depth ) const = 0; + + /** The world does not agree on whether white space should be kept or + not. In order to make everyone happy, these global, static functions + are provided to set whether or not TinyXml will condense all white space + into a single space or not. The default is to condense. Note changing this + value is not thread safe. + */ + static void SetCondenseWhiteSpace( bool condense ) { condenseWhiteSpace = condense; } + + /// Return the current white space setting. + static bool IsWhiteSpaceCondensed() { return condenseWhiteSpace; } + + /** Return the position, in the original source file, of this node or attribute. + The row and column are 1-based. (That is the first row and first column is + 1,1). If the returns values are 0 or less, then the parser does not have + a row and column value. + + Generally, the row and column value will be set when the TiXmlDocument::Load(), + TiXmlDocument::LoadFile(), or any TiXmlNode::Parse() is called. It will NOT be set + when the DOM was created from operator>>. + + The values reflect the initial load. Once the DOM is modified programmatically + (by adding or changing nodes and attributes) the new values will NOT update to + reflect changes in the document. + + There is a minor performance cost to computing the row and column. Computation + can be disabled if TiXmlDocument::SetTabSize() is called with 0 as the value. + + @sa TiXmlDocument::SetTabSize() + */ + int Row() const { return location.row + 1; } + int Column() const { return location.col + 1; } ///< See Row() + + void SetUserData( void* user ) { userData = user; } ///< Set a pointer to arbitrary user data. + void* GetUserData() { return userData; } ///< Get a pointer to arbitrary user data. + const void* GetUserData() const { return userData; } ///< Get a pointer to arbitrary user data. + + // Table that returs, for a given lead byte, the total number of bytes + // in the UTF-8 sequence. + static const int utf8ByteTable[256]; + + virtual const char* Parse( const char* p, + TiXmlParsingData* data, + TiXmlEncoding encoding /*= TIXML_ENCODING_UNKNOWN */ ) = 0; + + /** Expands entities in a string. Note this should not contian the tag's '<', '>', etc, + or they will be transformed into entities! + */ + static void EncodeString( const TIXML_STRING& str, TIXML_STRING* out ); + + enum + { + TIXML_NO_ERROR = 0, + TIXML_ERROR, + TIXML_ERROR_OPENING_FILE, + TIXML_ERROR_PARSING_ELEMENT, + TIXML_ERROR_FAILED_TO_READ_ELEMENT_NAME, + TIXML_ERROR_READING_ELEMENT_VALUE, + TIXML_ERROR_READING_ATTRIBUTES, + TIXML_ERROR_PARSING_EMPTY, + TIXML_ERROR_READING_END_TAG, + TIXML_ERROR_PARSING_UNKNOWN, + TIXML_ERROR_PARSING_COMMENT, + TIXML_ERROR_PARSING_DECLARATION, + TIXML_ERROR_DOCUMENT_EMPTY, + TIXML_ERROR_EMBEDDED_NULL, + TIXML_ERROR_PARSING_CDATA, + TIXML_ERROR_DOCUMENT_TOP_ONLY, + + TIXML_ERROR_STRING_COUNT + }; + +protected: + + static const char* SkipWhiteSpace( const char*, TiXmlEncoding encoding ); + + inline static bool IsWhiteSpace( char c ) + { + return ( isspace( (unsigned char) c ) || c == '\n' || c == '\r' ); + } + inline static bool IsWhiteSpace( int c ) + { + if ( c < 256 ) + return IsWhiteSpace( (char) c ); + return false; // Again, only truly correct for English/Latin...but usually works. + } + + #ifdef TIXML_USE_STL + static bool StreamWhiteSpace( std::istream * in, TIXML_STRING * tag ); + static bool StreamTo( std::istream * in, int character, TIXML_STRING * tag ); + #endif + + /* Reads an XML name into the string provided. Returns + a pointer just past the last character of the name, + or 0 if the function has an error. + */ + static const char* ReadName( const char* p, TIXML_STRING* name, TiXmlEncoding encoding ); + + /* Reads text. Returns a pointer past the given end tag. + Wickedly complex options, but it keeps the (sensitive) code in one place. + */ + static const char* ReadText( const char* in, // where to start + TIXML_STRING* text, // the string read + bool ignoreWhiteSpace, // whether to keep the white space + const char* endTag, // what ends this text + bool ignoreCase, // whether to ignore case in the end tag + TiXmlEncoding encoding ); // the current encoding + + // If an entity has been found, transform it into a character. + static const char* GetEntity( const char* in, char* value, int* length, TiXmlEncoding encoding ); + + // Get a character, while interpreting entities. + // The length can be from 0 to 4 bytes. + inline static const char* GetChar( const char* p, char* _value, int* length, TiXmlEncoding encoding ) + { + assert( p ); + if ( encoding == TIXML_ENCODING_UTF8 ) + { + *length = utf8ByteTable[ *((const unsigned char*)p) ]; + assert( *length >= 0 && *length < 5 ); + } + else + { + *length = 1; + } + + if ( *length == 1 ) + { + if ( *p == '&' ) + return GetEntity( p, _value, length, encoding ); + *_value = *p; + return p+1; + } + else if ( *length ) + { + //strncpy( _value, p, *length ); // lots of compilers don't like this function (unsafe), + // and the null terminator isn't needed + for( int i=0; p[i] && i<*length; ++i ) { + _value[i] = p[i]; + } + return p + (*length); + } + else + { + // Not valid text. + return 0; + } + } + + // Return true if the next characters in the stream are any of the endTag sequences. + // Ignore case only works for english, and should only be relied on when comparing + // to English words: StringEqual( p, "version", true ) is fine. + static bool StringEqual( const char* p, + const char* endTag, + bool ignoreCase, + TiXmlEncoding encoding ); + + static const char* errorString[ TIXML_ERROR_STRING_COUNT ]; + + TiXmlCursor location; + + /// Field containing a generic user pointer + void* userData; + + // None of these methods are reliable for any language except English. + // Good for approximation, not great for accuracy. + static int IsAlpha( unsigned char anyByte, TiXmlEncoding encoding ); + static int IsAlphaNum( unsigned char anyByte, TiXmlEncoding encoding ); + inline static int ToLower( int v, TiXmlEncoding encoding ) + { + if ( encoding == TIXML_ENCODING_UTF8 ) + { + if ( v < 128 ) return tolower( v ); + return v; + } + else + { + return tolower( v ); + } + } + static void ConvertUTF32ToUTF8( unsigned long input, char* output, int* length ); + +private: + TiXmlBase( const TiXmlBase& ); // not implemented. + void operator=( const TiXmlBase& base ); // not allowed. + + struct Entity + { + const char* str; + unsigned int strLength; + char chr; + }; + enum + { + NUM_ENTITY = 5, + MAX_ENTITY_LENGTH = 6 + + }; + static Entity entity[ NUM_ENTITY ]; + static bool condenseWhiteSpace; +}; + + +/** The parent class for everything in the Document Object Model. + (Except for attributes). + Nodes have siblings, a parent, and children. A node can be + in a document, or stand on its own. The type of a TiXmlNode + can be queried, and it can be cast to its more defined type. +*/ +class TiXmlNode : public TiXmlBase +{ + friend class TiXmlDocument; + friend class TiXmlElement; + +public: + #ifdef TIXML_USE_STL + + /** An input stream operator, for every class. Tolerant of newlines and + formatting, but doesn't expect them. + */ + friend std::istream& operator >> (std::istream& in, TiXmlNode& base); + + /** An output stream operator, for every class. Note that this outputs + without any newlines or formatting, as opposed to Print(), which + includes tabs and new lines. + + The operator<< and operator>> are not completely symmetric. Writing + a node to a stream is very well defined. You'll get a nice stream + of output, without any extra whitespace or newlines. + + But reading is not as well defined. (As it always is.) If you create + a TiXmlElement (for example) and read that from an input stream, + the text needs to define an element or junk will result. This is + true of all input streams, but it's worth keeping in mind. + + A TiXmlDocument will read nodes until it reads a root element, and + all the children of that root element. + */ + friend std::ostream& operator<< (std::ostream& out, const TiXmlNode& base); + + /// Appends the XML node or attribute to a std::string. + friend std::string& operator<< (std::string& out, const TiXmlNode& base ); + + #endif + + /** The types of XML nodes supported by TinyXml. (All the + unsupported types are picked up by UNKNOWN.) + */ + enum NodeType + { + TINYXML_DOCUMENT, + TINYXML_ELEMENT, + TINYXML_COMMENT, + TINYXML_UNKNOWN, + TINYXML_TEXT, + TINYXML_DECLARATION, + TINYXML_TYPECOUNT + }; + + virtual ~TiXmlNode(); + + /** The meaning of 'value' changes for the specific type of + TiXmlNode. + @verbatim + Document: filename of the xml file + Element: name of the element + Comment: the comment text + Unknown: the tag contents + Text: the text string + @endverbatim + + The subclasses will wrap this function. + */ + const char *Value() const { return value.c_str (); } + + #ifdef TIXML_USE_STL + /** Return Value() as a std::string. If you only use STL, + this is more efficient than calling Value(). + Only available in STL mode. + */ + const std::string& ValueStr() const { return value; } + #endif + + const TIXML_STRING& ValueTStr() const { return value; } + + /** Changes the value of the node. Defined as: + @verbatim + Document: filename of the xml file + Element: name of the element + Comment: the comment text + Unknown: the tag contents + Text: the text string + @endverbatim + */ + void SetValue(const char * _value) { value = _value;} + + #ifdef TIXML_USE_STL + /// STL std::string form. + void SetValue( const std::string& _value ) { value = _value; } + #endif + + /// Delete all the children of this node. Does not affect 'this'. + void Clear(); + + /// One step up the DOM. + TiXmlNode* Parent() { return parent; } + const TiXmlNode* Parent() const { return parent; } + + const TiXmlNode* FirstChild() const { return firstChild; } ///< The first child of this node. Will be null if there are no children. + TiXmlNode* FirstChild() { return firstChild; } + const TiXmlNode* FirstChild( const char * value ) const; ///< The first child of this node with the matching 'value'. Will be null if none found. + /// The first child of this node with the matching 'value'. Will be null if none found. + TiXmlNode* FirstChild( const char * _value ) { + // Call through to the const version - safe since nothing is changed. Exiting syntax: cast this to a const (always safe) + // call the method, cast the return back to non-const. + return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->FirstChild( _value )); + } + const TiXmlNode* LastChild() const { return lastChild; } /// The last child of this node. Will be null if there are no children. + TiXmlNode* LastChild() { return lastChild; } + + const TiXmlNode* LastChild( const char * value ) const; /// The last child of this node matching 'value'. Will be null if there are no children. + TiXmlNode* LastChild( const char * _value ) { + return const_cast< TiXmlNode* > ((const_cast< const TiXmlNode* >(this))->LastChild( _value )); + } + + #ifdef TIXML_USE_STL + const TiXmlNode* FirstChild( const std::string& _value ) const { return FirstChild (_value.c_str ()); } ///< STL std::string form. + TiXmlNode* FirstChild( const std::string& _value ) { return FirstChild (_value.c_str ()); } ///< STL std::string form. + const TiXmlNode* LastChild( const std::string& _value ) const { return LastChild (_value.c_str ()); } ///< STL std::string form. + TiXmlNode* LastChild( const std::string& _value ) { return LastChild (_value.c_str ()); } ///< STL std::string form. + #endif + + /** An alternate way to walk the children of a node. + One way to iterate over nodes is: + @verbatim + for( child = parent->FirstChild(); child; child = child->NextSibling() ) + @endverbatim + + IterateChildren does the same thing with the syntax: + @verbatim + child = 0; + while( child = parent->IterateChildren( child ) ) + @endverbatim + + IterateChildren takes the previous child as input and finds + the next one. If the previous child is null, it returns the + first. IterateChildren will return null when done. + */ + const TiXmlNode* IterateChildren( const TiXmlNode* previous ) const; + TiXmlNode* IterateChildren( const TiXmlNode* previous ) { + return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( previous ) ); + } + + /// This flavor of IterateChildren searches for children with a particular 'value' + const TiXmlNode* IterateChildren( const char * value, const TiXmlNode* previous ) const; + TiXmlNode* IterateChildren( const char * _value, const TiXmlNode* previous ) { + return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->IterateChildren( _value, previous ) ); + } + + #ifdef TIXML_USE_STL + const TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) const { return IterateChildren (_value.c_str (), previous); } ///< STL std::string form. + TiXmlNode* IterateChildren( const std::string& _value, const TiXmlNode* previous ) { return IterateChildren (_value.c_str (), previous); } ///< STL std::string form. + #endif + + /** Add a new node related to this. Adds a child past the LastChild. + Returns a pointer to the new object or NULL if an error occured. + */ + TiXmlNode* InsertEndChild( const TiXmlNode& addThis ); + + + /** Add a new node related to this. Adds a child past the LastChild. + + NOTE: the node to be added is passed by pointer, and will be + henceforth owned (and deleted) by tinyXml. This method is efficient + and avoids an extra copy, but should be used with care as it + uses a different memory model than the other insert functions. + + @sa InsertEndChild + */ + TiXmlNode* LinkEndChild( TiXmlNode* addThis ); + + /** Add a new node related to this. Adds a child before the specified child. + Returns a pointer to the new object or NULL if an error occured. + */ + TiXmlNode* InsertBeforeChild( TiXmlNode* beforeThis, const TiXmlNode& addThis ); + + /** Add a new node related to this. Adds a child after the specified child. + Returns a pointer to the new object or NULL if an error occured. + */ + TiXmlNode* InsertAfterChild( TiXmlNode* afterThis, const TiXmlNode& addThis ); + + /** Replace a child of this node. + Returns a pointer to the new object or NULL if an error occured. + */ + TiXmlNode* ReplaceChild( TiXmlNode* replaceThis, const TiXmlNode& withThis ); + + /// Delete a child of this node. + bool RemoveChild( TiXmlNode* removeThis ); + + /// Navigate to a sibling node. + const TiXmlNode* PreviousSibling() const { return prev; } + TiXmlNode* PreviousSibling() { return prev; } + + /// Navigate to a sibling node. + const TiXmlNode* PreviousSibling( const char * ) const; + TiXmlNode* PreviousSibling( const char *_prev ) { + return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->PreviousSibling( _prev ) ); + } + + #ifdef TIXML_USE_STL + const TiXmlNode* PreviousSibling( const std::string& _value ) const { return PreviousSibling (_value.c_str ()); } ///< STL std::string form. + TiXmlNode* PreviousSibling( const std::string& _value ) { return PreviousSibling (_value.c_str ()); } ///< STL std::string form. + const TiXmlNode* NextSibling( const std::string& _value) const { return NextSibling (_value.c_str ()); } ///< STL std::string form. + TiXmlNode* NextSibling( const std::string& _value) { return NextSibling (_value.c_str ()); } ///< STL std::string form. + #endif + + /// Navigate to a sibling node. + const TiXmlNode* NextSibling() const { return next; } + TiXmlNode* NextSibling() { return next; } + + /// Navigate to a sibling node with the given 'value'. + const TiXmlNode* NextSibling( const char * ) const; + TiXmlNode* NextSibling( const char* _next ) { + return const_cast< TiXmlNode* >( (const_cast< const TiXmlNode* >(this))->NextSibling( _next ) ); + } + + /** Convenience function to get through elements. + Calls NextSibling and ToElement. Will skip all non-Element + nodes. Returns 0 if there is not another element. + */ + const TiXmlElement* NextSiblingElement() const; + TiXmlElement* NextSiblingElement() { + return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement() ); + } + + /** Convenience function to get through elements. + Calls NextSibling and ToElement. Will skip all non-Element + nodes. Returns 0 if there is not another element. + */ + const TiXmlElement* NextSiblingElement( const char * ) const; + TiXmlElement* NextSiblingElement( const char *_next ) { + return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->NextSiblingElement( _next ) ); + } + + #ifdef TIXML_USE_STL + const TiXmlElement* NextSiblingElement( const std::string& _value) const { return NextSiblingElement (_value.c_str ()); } ///< STL std::string form. + TiXmlElement* NextSiblingElement( const std::string& _value) { return NextSiblingElement (_value.c_str ()); } ///< STL std::string form. + #endif + + /// Convenience function to get through elements. + const TiXmlElement* FirstChildElement() const; + TiXmlElement* FirstChildElement() { + return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement() ); + } + + /// Convenience function to get through elements. + const TiXmlElement* FirstChildElement( const char * _value ) const; + TiXmlElement* FirstChildElement( const char * _value ) { + return const_cast< TiXmlElement* >( (const_cast< const TiXmlNode* >(this))->FirstChildElement( _value ) ); + } + + #ifdef TIXML_USE_STL + const TiXmlElement* FirstChildElement( const std::string& _value ) const { return FirstChildElement (_value.c_str ()); } ///< STL std::string form. + TiXmlElement* FirstChildElement( const std::string& _value ) { return FirstChildElement (_value.c_str ()); } ///< STL std::string form. + #endif + + /** Query the type (as an enumerated value, above) of this node. + The possible types are: TINYXML_DOCUMENT, TINYXML_ELEMENT, TINYXML_COMMENT, + TINYXML_UNKNOWN, TINYXML_TEXT, and TINYXML_DECLARATION. + */ + int Type() const { return type; } + + /** Return a pointer to the Document this node lives in. + Returns null if not in a document. + */ + const TiXmlDocument* GetDocument() const; + TiXmlDocument* GetDocument() { + return const_cast< TiXmlDocument* >( (const_cast< const TiXmlNode* >(this))->GetDocument() ); + } + + /// Returns true if this node has no children. + bool NoChildren() const { return !firstChild; } + + virtual const TiXmlDocument* ToDocument() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual const TiXmlElement* ToElement() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual const TiXmlComment* ToComment() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual const TiXmlUnknown* ToUnknown() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual const TiXmlText* ToText() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual const TiXmlDeclaration* ToDeclaration() const { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + + virtual TiXmlDocument* ToDocument() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual TiXmlElement* ToElement() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual TiXmlComment* ToComment() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual TiXmlUnknown* ToUnknown() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual TiXmlText* ToText() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + virtual TiXmlDeclaration* ToDeclaration() { return 0; } ///< Cast to a more defined type. Will return null if not of the requested type. + + /** Create an exact duplicate of this node and return it. The memory must be deleted + by the caller. + */ + virtual TiXmlNode* Clone() const = 0; + + /** Accept a hierchical visit the nodes in the TinyXML DOM. Every node in the + XML tree will be conditionally visited and the host will be called back + via the TiXmlVisitor interface. + + This is essentially a SAX interface for TinyXML. (Note however it doesn't re-parse + the XML for the callbacks, so the performance of TinyXML is unchanged by using this + interface versus any other.) + + The interface has been based on ideas from: + + - http://www.saxproject.org/ + - http://c2.com/cgi/wiki?HierarchicalVisitorPattern + + Which are both good references for "visiting". + + An example of using Accept(): + @verbatim + TiXmlPrinter printer; + tinyxmlDoc.Accept( &printer ); + const char* xmlcstr = printer.CStr(); + @endverbatim + */ + virtual bool Accept( TiXmlVisitor* visitor ) const = 0; + +protected: + TiXmlNode( NodeType _type ); + + // Copy to the allocated object. Shared functionality between Clone, Copy constructor, + // and the assignment operator. + void CopyTo( TiXmlNode* target ) const; + + #ifdef TIXML_USE_STL + // The real work of the input operator. + virtual void StreamIn( std::istream* in, TIXML_STRING* tag ) = 0; + #endif + + // Figure out what is at *p, and parse it. Returns null if it is not an xml node. + TiXmlNode* Identify( const char* start, TiXmlEncoding encoding ); + + TiXmlNode* parent; + NodeType type; + + TiXmlNode* firstChild; + TiXmlNode* lastChild; + + TIXML_STRING value; + + TiXmlNode* prev; + TiXmlNode* next; + +private: + TiXmlNode( const TiXmlNode& ); // not implemented. + void operator=( const TiXmlNode& base ); // not allowed. +}; + + +/** An attribute is a name-value pair. Elements have an arbitrary + number of attributes, each with a unique name. + + @note The attributes are not TiXmlNodes, since they are not + part of the tinyXML document object model. There are other + suggested ways to look at this problem. +*/ +class TiXmlAttribute : public TiXmlBase +{ + friend class TiXmlAttributeSet; + +public: + /// Construct an empty attribute. + TiXmlAttribute() : TiXmlBase() + { + document = 0; + prev = next = 0; + } + + #ifdef TIXML_USE_STL + /// std::string constructor. + TiXmlAttribute( const std::string& _name, const std::string& _value ) + { + name = _name; + value = _value; + document = 0; + prev = next = 0; + } + #endif + + /// Construct an attribute with a name and value. + TiXmlAttribute( const char * _name, const char * _value ) + { + name = _name; + value = _value; + document = 0; + prev = next = 0; + } + + const char* Name() const { return name.c_str(); } ///< Return the name of this attribute. + const char* Value() const { return value.c_str(); } ///< Return the value of this attribute. + #ifdef TIXML_USE_STL + const std::string& ValueStr() const { return value; } ///< Return the value of this attribute. + #endif + int IntValue() const; ///< Return the value of this attribute, converted to an integer. + double DoubleValue() const; ///< Return the value of this attribute, converted to a double. + + // Get the tinyxml string representation + const TIXML_STRING& NameTStr() const { return name; } + + /** QueryIntValue examines the value string. It is an alternative to the + IntValue() method with richer error checking. + If the value is an integer, it is stored in 'value' and + the call returns TIXML_SUCCESS. If it is not + an integer, it returns TIXML_WRONG_TYPE. + + A specialized but useful call. Note that for success it returns 0, + which is the opposite of almost all other TinyXml calls. + */ + int QueryIntValue( int* _value ) const; + /// QueryDoubleValue examines the value string. See QueryIntValue(). + int QueryDoubleValue( double* _value ) const; + + void SetName( const char* _name ) { name = _name; } ///< Set the name of this attribute. + void SetValue( const char* _value ) { value = _value; } ///< Set the value. + + void SetIntValue( int _value ); ///< Set the value from an integer. + void SetDoubleValue( double _value ); ///< Set the value from a double. + + #ifdef TIXML_USE_STL + /// STL std::string form. + void SetName( const std::string& _name ) { name = _name; } + /// STL std::string form. + void SetValue( const std::string& _value ) { value = _value; } + #endif + + /// Get the next sibling attribute in the DOM. Returns null at end. + const TiXmlAttribute* Next() const; + TiXmlAttribute* Next() { + return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Next() ); + } + + /// Get the previous sibling attribute in the DOM. Returns null at beginning. + const TiXmlAttribute* Previous() const; + TiXmlAttribute* Previous() { + return const_cast< TiXmlAttribute* >( (const_cast< const TiXmlAttribute* >(this))->Previous() ); + } + + bool operator==( const TiXmlAttribute& rhs ) const { return rhs.name == name; } + bool operator<( const TiXmlAttribute& rhs ) const { return name < rhs.name; } + bool operator>( const TiXmlAttribute& rhs ) const { return name > rhs.name; } + + /* Attribute parsing starts: first letter of the name + returns: the next char after the value end quote + */ + virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); + + // Prints this Attribute to a FILE stream. + virtual void Print( FILE* cfile, int depth ) const { + Print( cfile, depth, 0 ); + } + void Print( FILE* cfile, int depth, TIXML_STRING* str ) const; + + // [internal use] + // Set the document pointer so the attribute can report errors. + void SetDocument( TiXmlDocument* doc ) { document = doc; } + +private: + TiXmlAttribute( const TiXmlAttribute& ); // not implemented. + void operator=( const TiXmlAttribute& base ); // not allowed. + + TiXmlDocument* document; // A pointer back to a document, for error reporting. + TIXML_STRING name; + TIXML_STRING value; + TiXmlAttribute* prev; + TiXmlAttribute* next; +}; + + +/* A class used to manage a group of attributes. + It is only used internally, both by the ELEMENT and the DECLARATION. + + The set can be changed transparent to the Element and Declaration + classes that use it, but NOT transparent to the Attribute + which has to implement a next() and previous() method. Which makes + it a bit problematic and prevents the use of STL. + + This version is implemented with circular lists because: + - I like circular lists + - it demonstrates some independence from the (typical) doubly linked list. +*/ +class TiXmlAttributeSet +{ +public: + TiXmlAttributeSet(); + ~TiXmlAttributeSet(); + + void Add( TiXmlAttribute* attribute ); + void Remove( TiXmlAttribute* attribute ); + + const TiXmlAttribute* First() const { return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; } + TiXmlAttribute* First() { return ( sentinel.next == &sentinel ) ? 0 : sentinel.next; } + const TiXmlAttribute* Last() const { return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; } + TiXmlAttribute* Last() { return ( sentinel.prev == &sentinel ) ? 0 : sentinel.prev; } + + TiXmlAttribute* Find( const char* _name ) const; + TiXmlAttribute* FindOrCreate( const char* _name ); + +# ifdef TIXML_USE_STL + TiXmlAttribute* Find( const std::string& _name ) const; + TiXmlAttribute* FindOrCreate( const std::string& _name ); +# endif + + +private: + //*ME: Because of hidden/disabled copy-construktor in TiXmlAttribute (sentinel-element), + //*ME: this class must be also use a hidden/disabled copy-constructor !!! + TiXmlAttributeSet( const TiXmlAttributeSet& ); // not allowed + void operator=( const TiXmlAttributeSet& ); // not allowed (as TiXmlAttribute) + + TiXmlAttribute sentinel; +}; + + +/** The element is a container class. It has a value, the element name, + and can contain other elements, text, comments, and unknowns. + Elements also contain an arbitrary number of attributes. +*/ +class TiXmlElement : public TiXmlNode +{ +public: + /// Construct an element. + TiXmlElement (const char * in_value); + + #ifdef TIXML_USE_STL + /// std::string constructor. + TiXmlElement( const std::string& _value ); + #endif + + TiXmlElement( const TiXmlElement& ); + + TiXmlElement& operator=( const TiXmlElement& base ); + + virtual ~TiXmlElement(); + + /** Given an attribute name, Attribute() returns the value + for the attribute of that name, or null if none exists. + */ + const char* Attribute( const char* name ) const; + + /** Given an attribute name, Attribute() returns the value + for the attribute of that name, or null if none exists. + If the attribute exists and can be converted to an integer, + the integer value will be put in the return 'i', if 'i' + is non-null. + */ + const char* Attribute( const char* name, int* i ) const; + + /** Given an attribute name, Attribute() returns the value + for the attribute of that name, or null if none exists. + If the attribute exists and can be converted to an double, + the double value will be put in the return 'd', if 'd' + is non-null. + */ + const char* Attribute( const char* name, double* d ) const; + + /** QueryIntAttribute examines the attribute - it is an alternative to the + Attribute() method with richer error checking. + If the attribute is an integer, it is stored in 'value' and + the call returns TIXML_SUCCESS. If it is not + an integer, it returns TIXML_WRONG_TYPE. If the attribute + does not exist, then TIXML_NO_ATTRIBUTE is returned. + */ + int QueryIntAttribute( const char* name, int* _value ) const; + /// QueryUnsignedAttribute examines the attribute - see QueryIntAttribute(). + int QueryUnsignedAttribute( const char* name, unsigned* _value ) const; + /** QueryBoolAttribute examines the attribute - see QueryIntAttribute(). + Note that '1', 'true', or 'yes' are considered true, while '0', 'false' + and 'no' are considered false. + */ + int QueryBoolAttribute( const char* name, bool* _value ) const; + /// QueryDoubleAttribute examines the attribute - see QueryIntAttribute(). + int QueryDoubleAttribute( const char* name, double* _value ) const; + /// QueryFloatAttribute examines the attribute - see QueryIntAttribute(). + int QueryFloatAttribute( const char* name, float* _value ) const { + double d; + int result = QueryDoubleAttribute( name, &d ); + if ( result == TIXML_SUCCESS ) { + *_value = (float)d; + } + return result; + } + + #ifdef TIXML_USE_STL + /// QueryStringAttribute examines the attribute - see QueryIntAttribute(). + int QueryStringAttribute( const char* name, std::string* _value ) const { + const char* cstr = Attribute( name ); + if ( cstr ) { + *_value = std::string( cstr ); + return TIXML_SUCCESS; + } + return TIXML_NO_ATTRIBUTE; + } + + /** Template form of the attribute query which will try to read the + attribute into the specified type. Very easy, very powerful, but + be careful to make sure to call this with the correct type. + + NOTE: This method doesn't work correctly for 'string' types that contain spaces. + + @return TIXML_SUCCESS, TIXML_WRONG_TYPE, or TIXML_NO_ATTRIBUTE + */ + template< typename T > int QueryValueAttribute( const std::string& name, T* outValue ) const + { + const TiXmlAttribute* node = attributeSet.Find( name ); + if ( !node ) + return TIXML_NO_ATTRIBUTE; + + std::stringstream sstream( node->ValueStr() ); + sstream >> *outValue; + if ( !sstream.fail() ) + return TIXML_SUCCESS; + return TIXML_WRONG_TYPE; + } + + int QueryValueAttribute( const std::string& name, std::string* outValue ) const + { + const TiXmlAttribute* node = attributeSet.Find( name ); + if ( !node ) + return TIXML_NO_ATTRIBUTE; + *outValue = node->ValueStr(); + return TIXML_SUCCESS; + } + #endif + + /** Sets an attribute of name to a given value. The attribute + will be created if it does not exist, or changed if it does. + */ + void SetAttribute( const char* name, const char * _value ); + + #ifdef TIXML_USE_STL + const std::string* Attribute( const std::string& name ) const; + const std::string* Attribute( const std::string& name, int* i ) const; + const std::string* Attribute( const std::string& name, double* d ) const; + int QueryIntAttribute( const std::string& name, int* _value ) const; + int QueryDoubleAttribute( const std::string& name, double* _value ) const; + + /// STL std::string form. + void SetAttribute( const std::string& name, const std::string& _value ); + ///< STL std::string form. + void SetAttribute( const std::string& name, int _value ); + ///< STL std::string form. + void SetDoubleAttribute( const std::string& name, double value ); + #endif + + /** Sets an attribute of name to a given value. The attribute + will be created if it does not exist, or changed if it does. + */ + void SetAttribute( const char * name, int value ); + + /** Sets an attribute of name to a given value. The attribute + will be created if it does not exist, or changed if it does. + */ + void SetDoubleAttribute( const char * name, double value ); + + /** Deletes an attribute with the given name. + */ + void RemoveAttribute( const char * name ); + #ifdef TIXML_USE_STL + void RemoveAttribute( const std::string& name ) { RemoveAttribute (name.c_str ()); } ///< STL std::string form. + #endif + + const TiXmlAttribute* FirstAttribute() const { return attributeSet.First(); } ///< Access the first attribute in this element. + TiXmlAttribute* FirstAttribute() { return attributeSet.First(); } + const TiXmlAttribute* LastAttribute() const { return attributeSet.Last(); } ///< Access the last attribute in this element. + TiXmlAttribute* LastAttribute() { return attributeSet.Last(); } + + /** Convenience function for easy access to the text inside an element. Although easy + and concise, GetText() is limited compared to getting the TiXmlText child + and accessing it directly. + + If the first child of 'this' is a TiXmlText, the GetText() + returns the character string of the Text node, else null is returned. + + This is a convenient method for getting the text of simple contained text: + @verbatim + This is text + const char* str = fooElement->GetText(); + @endverbatim + + 'str' will be a pointer to "This is text". + + Note that this function can be misleading. If the element foo was created from + this XML: + @verbatim + This is text + @endverbatim + + then the value of str would be null. The first child node isn't a text node, it is + another element. From this XML: + @verbatim + This is text + @endverbatim + GetText() will return "This is ". + + WARNING: GetText() accesses a child node - don't become confused with the + similarly named TiXmlHandle::Text() and TiXmlNode::ToText() which are + safe type casts on the referenced node. + */ + const char* GetText() const; + + /// Creates a new Element and returns it - the returned element is a copy. + virtual TiXmlNode* Clone() const; + // Print the Element to a FILE stream. + virtual void Print( FILE* cfile, int depth ) const; + + /* Attribtue parsing starts: next char past '<' + returns: next char past '>' + */ + virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); + + virtual const TiXmlElement* ToElement() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + virtual TiXmlElement* ToElement() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + + /** Walk the XML tree visiting this node and all of its children. + */ + virtual bool Accept( TiXmlVisitor* visitor ) const; + +protected: + + void CopyTo( TiXmlElement* target ) const; + void ClearThis(); // like clear, but initializes 'this' object as well + + // Used to be public [internal use] + #ifdef TIXML_USE_STL + virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); + #endif + /* [internal use] + Reads the "value" of the element -- another element, or text. + This should terminate with the current end tag. + */ + const char* ReadValue( const char* in, TiXmlParsingData* prevData, TiXmlEncoding encoding ); + +private: + TiXmlAttributeSet attributeSet; +}; + + +/** An XML comment. +*/ +class TiXmlComment : public TiXmlNode +{ +public: + /// Constructs an empty comment. + TiXmlComment() : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) {} + /// Construct a comment from text. + TiXmlComment( const char* _value ) : TiXmlNode( TiXmlNode::TINYXML_COMMENT ) { + SetValue( _value ); + } + TiXmlComment( const TiXmlComment& ); + TiXmlComment& operator=( const TiXmlComment& base ); + + virtual ~TiXmlComment() {} + + /// Returns a copy of this Comment. + virtual TiXmlNode* Clone() const; + // Write this Comment to a FILE stream. + virtual void Print( FILE* cfile, int depth ) const; + + /* Attribtue parsing starts: at the ! of the !-- + returns: next char past '>' + */ + virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); + + virtual const TiXmlComment* ToComment() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + virtual TiXmlComment* ToComment() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + + /** Walk the XML tree visiting this node and all of its children. + */ + virtual bool Accept( TiXmlVisitor* visitor ) const; + +protected: + void CopyTo( TiXmlComment* target ) const; + + // used to be public + #ifdef TIXML_USE_STL + virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); + #endif +// virtual void StreamOut( TIXML_OSTREAM * out ) const; + +private: + +}; + + +/** XML text. A text node can have 2 ways to output the next. "normal" output + and CDATA. It will default to the mode it was parsed from the XML file and + you generally want to leave it alone, but you can change the output mode with + SetCDATA() and query it with CDATA(). +*/ +class TiXmlText : public TiXmlNode +{ + friend class TiXmlElement; +public: + /** Constructor for text element. By default, it is treated as + normal, encoded text. If you want it be output as a CDATA text + element, set the parameter _cdata to 'true' + */ + TiXmlText (const char * initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT) + { + SetValue( initValue ); + cdata = false; + } + virtual ~TiXmlText() {} + + #ifdef TIXML_USE_STL + /// Constructor. + TiXmlText( const std::string& initValue ) : TiXmlNode (TiXmlNode::TINYXML_TEXT) + { + SetValue( initValue ); + cdata = false; + } + #endif + + TiXmlText( const TiXmlText& copy ) : TiXmlNode( TiXmlNode::TINYXML_TEXT ) { copy.CopyTo( this ); } + TiXmlText& operator=( const TiXmlText& base ) { base.CopyTo( this ); return *this; } + + // Write this text object to a FILE stream. + virtual void Print( FILE* cfile, int depth ) const; + + /// Queries whether this represents text using a CDATA section. + bool CDATA() const { return cdata; } + /// Turns on or off a CDATA representation of text. + void SetCDATA( bool _cdata ) { cdata = _cdata; } + + virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); + + virtual const TiXmlText* ToText() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + virtual TiXmlText* ToText() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + + /** Walk the XML tree visiting this node and all of its children. + */ + virtual bool Accept( TiXmlVisitor* content ) const; + +protected : + /// [internal use] Creates a new Element and returns it. + virtual TiXmlNode* Clone() const; + void CopyTo( TiXmlText* target ) const; + + bool Blank() const; // returns true if all white space and new lines + // [internal use] + #ifdef TIXML_USE_STL + virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); + #endif + +private: + bool cdata; // true if this should be input and output as a CDATA style text element +}; + + +/** In correct XML the declaration is the first entry in the file. + @verbatim + + @endverbatim + + TinyXml will happily read or write files without a declaration, + however. There are 3 possible attributes to the declaration: + version, encoding, and standalone. + + Note: In this version of the code, the attributes are + handled as special cases, not generic attributes, simply + because there can only be at most 3 and they are always the same. +*/ +class TiXmlDeclaration : public TiXmlNode +{ +public: + /// Construct an empty declaration. + TiXmlDeclaration() : TiXmlNode( TiXmlNode::TINYXML_DECLARATION ) {} + +#ifdef TIXML_USE_STL + /// Constructor. + TiXmlDeclaration( const std::string& _version, + const std::string& _encoding, + const std::string& _standalone ); +#endif + + /// Construct. + TiXmlDeclaration( const char* _version, + const char* _encoding, + const char* _standalone ); + + TiXmlDeclaration( const TiXmlDeclaration& copy ); + TiXmlDeclaration& operator=( const TiXmlDeclaration& copy ); + + virtual ~TiXmlDeclaration() {} + + /// Version. Will return an empty string if none was found. + const char *Version() const { return version.c_str (); } + /// Encoding. Will return an empty string if none was found. + const char *Encoding() const { return encoding.c_str (); } + /// Is this a standalone document? + const char *Standalone() const { return standalone.c_str (); } + + /// Creates a copy of this Declaration and returns it. + virtual TiXmlNode* Clone() const; + // Print this declaration to a FILE stream. + virtual void Print( FILE* cfile, int depth, TIXML_STRING* str ) const; + virtual void Print( FILE* cfile, int depth ) const { + Print( cfile, depth, 0 ); + } + + virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); + + virtual const TiXmlDeclaration* ToDeclaration() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + virtual TiXmlDeclaration* ToDeclaration() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + + /** Walk the XML tree visiting this node and all of its children. + */ + virtual bool Accept( TiXmlVisitor* visitor ) const; + +protected: + void CopyTo( TiXmlDeclaration* target ) const; + // used to be public + #ifdef TIXML_USE_STL + virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); + #endif + +private: + + TIXML_STRING version; + TIXML_STRING encoding; + TIXML_STRING standalone; +}; + + +/** Any tag that tinyXml doesn't recognize is saved as an + unknown. It is a tag of text, but should not be modified. + It will be written back to the XML, unchanged, when the file + is saved. + + DTD tags get thrown into TiXmlUnknowns. +*/ +class TiXmlUnknown : public TiXmlNode +{ +public: + TiXmlUnknown() : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN ) {} + virtual ~TiXmlUnknown() {} + + TiXmlUnknown( const TiXmlUnknown& copy ) : TiXmlNode( TiXmlNode::TINYXML_UNKNOWN ) { copy.CopyTo( this ); } + TiXmlUnknown& operator=( const TiXmlUnknown& copy ) { copy.CopyTo( this ); return *this; } + + /// Creates a copy of this Unknown and returns it. + virtual TiXmlNode* Clone() const; + // Print this Unknown to a FILE stream. + virtual void Print( FILE* cfile, int depth ) const; + + virtual const char* Parse( const char* p, TiXmlParsingData* data, TiXmlEncoding encoding ); + + virtual const TiXmlUnknown* ToUnknown() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + virtual TiXmlUnknown* ToUnknown() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + + /** Walk the XML tree visiting this node and all of its children. + */ + virtual bool Accept( TiXmlVisitor* content ) const; + +protected: + void CopyTo( TiXmlUnknown* target ) const; + + #ifdef TIXML_USE_STL + virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); + #endif + +private: + +}; + + +/** Always the top level node. A document binds together all the + XML pieces. It can be saved, loaded, and printed to the screen. + The 'value' of a document node is the xml file name. +*/ +class TiXmlDocument : public TiXmlNode +{ +public: + /// Create an empty document, that has no name. + TiXmlDocument(); + /// Create a document with a name. The name of the document is also the filename of the xml. + TiXmlDocument( const char * documentName ); + + #ifdef TIXML_USE_STL + /// Constructor. + TiXmlDocument( const std::string& documentName ); + #endif + + TiXmlDocument( const TiXmlDocument& copy ); + TiXmlDocument& operator=( const TiXmlDocument& copy ); + + virtual ~TiXmlDocument() {} + + /** Load a file using the current document value. + Returns true if successful. Will delete any existing + document data before loading. + */ + bool LoadFile( TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); + /// Save a file using the current document value. Returns true if successful. + bool SaveFile() const; + /// Load a file using the given filename. Returns true if successful. + bool LoadFile( const char * filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); + /// Save a file using the given filename. Returns true if successful. + bool SaveFile( const char * filename ) const; + /** Load a file using the given FILE*. Returns true if successful. Note that this method + doesn't stream - the entire object pointed at by the FILE* + will be interpreted as an XML file. TinyXML doesn't stream in XML from the current + file location. Streaming may be added in the future. + */ + bool LoadFile( FILE*, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); + /// Save a file using the given FILE*. Returns true if successful. + bool SaveFile( FILE* ) const; + + #ifdef TIXML_USE_STL + bool LoadFile( const std::string& filename, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ) ///< STL std::string version. + { + return LoadFile( filename.c_str(), encoding ); + } + bool SaveFile( const std::string& filename ) const ///< STL std::string version. + { + return SaveFile( filename.c_str() ); + } + #endif + + /** Parse the given null terminated block of xml data. Passing in an encoding to this + method (either TIXML_ENCODING_LEGACY or TIXML_ENCODING_UTF8 will force TinyXml + to use that encoding, regardless of what TinyXml might otherwise try to detect. + */ + virtual const char* Parse( const char* p, TiXmlParsingData* data = 0, TiXmlEncoding encoding = TIXML_DEFAULT_ENCODING ); + + /** Get the root element -- the only top level element -- of the document. + In well formed XML, there should only be one. TinyXml is tolerant of + multiple elements at the document level. + */ + const TiXmlElement* RootElement() const { return FirstChildElement(); } + TiXmlElement* RootElement() { return FirstChildElement(); } + + /** If an error occurs, Error will be set to true. Also, + - The ErrorId() will contain the integer identifier of the error (not generally useful) + - The ErrorDesc() method will return the name of the error. (very useful) + - The ErrorRow() and ErrorCol() will return the location of the error (if known) + */ + bool Error() const { return error; } + + /// Contains a textual (english) description of the error if one occurs. + const char * ErrorDesc() const { return errorDesc.c_str (); } + + /** Generally, you probably want the error string ( ErrorDesc() ). But if you + prefer the ErrorId, this function will fetch it. + */ + int ErrorId() const { return errorId; } + + /** Returns the location (if known) of the error. The first column is column 1, + and the first row is row 1. A value of 0 means the row and column wasn't applicable + (memory errors, for example, have no row/column) or the parser lost the error. (An + error in the error reporting, in that case.) + + @sa SetTabSize, Row, Column + */ + int ErrorRow() const { return errorLocation.row+1; } + int ErrorCol() const { return errorLocation.col+1; } ///< The column where the error occured. See ErrorRow() + + /** SetTabSize() allows the error reporting functions (ErrorRow() and ErrorCol()) + to report the correct values for row and column. It does not change the output + or input in any way. + + By calling this method, with a tab size + greater than 0, the row and column of each node and attribute is stored + when the file is loaded. Very useful for tracking the DOM back in to + the source file. + + The tab size is required for calculating the location of nodes. If not + set, the default of 4 is used. The tabsize is set per document. Setting + the tabsize to 0 disables row/column tracking. + + Note that row and column tracking is not supported when using operator>>. + + The tab size needs to be enabled before the parse or load. Correct usage: + @verbatim + TiXmlDocument doc; + doc.SetTabSize( 8 ); + doc.Load( "myfile.xml" ); + @endverbatim + + @sa Row, Column + */ + void SetTabSize( int _tabsize ) { tabsize = _tabsize; } + + int TabSize() const { return tabsize; } + + /** If you have handled the error, it can be reset with this call. The error + state is automatically cleared if you Parse a new XML block. + */ + void ClearError() { error = false; + errorId = 0; + errorDesc = ""; + errorLocation.row = errorLocation.col = 0; + //errorLocation.last = 0; + } + + /** Write the document to standard out using formatted printing ("pretty print"). */ + void Print() const { Print( stdout, 0 ); } + + /* Write the document to a string using formatted printing ("pretty print"). This + will allocate a character array (new char[]) and return it as a pointer. The + calling code pust call delete[] on the return char* to avoid a memory leak. + */ + //char* PrintToMemory() const; + + /// Print this Document to a FILE stream. + virtual void Print( FILE* cfile, int depth = 0 ) const; + // [internal use] + void SetError( int err, const char* errorLocation, TiXmlParsingData* prevData, TiXmlEncoding encoding ); + + virtual const TiXmlDocument* ToDocument() const { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + virtual TiXmlDocument* ToDocument() { return this; } ///< Cast to a more defined type. Will return null not of the requested type. + + /** Walk the XML tree visiting this node and all of its children. + */ + virtual bool Accept( TiXmlVisitor* content ) const; + +protected : + // [internal use] + virtual TiXmlNode* Clone() const; + #ifdef TIXML_USE_STL + virtual void StreamIn( std::istream * in, TIXML_STRING * tag ); + #endif + +private: + void CopyTo( TiXmlDocument* target ) const; + + bool error; + int errorId; + TIXML_STRING errorDesc; + int tabsize; + TiXmlCursor errorLocation; + bool useMicrosoftBOM; // the UTF-8 BOM were found when read. Note this, and try to write. +}; + + +/** + A TiXmlHandle is a class that wraps a node pointer with null checks; this is + an incredibly useful thing. Note that TiXmlHandle is not part of the TinyXml + DOM structure. It is a separate utility class. + + Take an example: + @verbatim + + + + + + + @endverbatim + + Assuming you want the value of "attributeB" in the 2nd "Child" element, it's very + easy to write a *lot* of code that looks like: + + @verbatim + TiXmlElement* root = document.FirstChildElement( "Document" ); + if ( root ) + { + TiXmlElement* element = root->FirstChildElement( "Element" ); + if ( element ) + { + TiXmlElement* child = element->FirstChildElement( "Child" ); + if ( child ) + { + TiXmlElement* child2 = child->NextSiblingElement( "Child" ); + if ( child2 ) + { + // Finally do something useful. + @endverbatim + + And that doesn't even cover "else" cases. TiXmlHandle addresses the verbosity + of such code. A TiXmlHandle checks for null pointers so it is perfectly safe + and correct to use: + + @verbatim + TiXmlHandle docHandle( &document ); + TiXmlElement* child2 = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", 1 ).ToElement(); + if ( child2 ) + { + // do something useful + @endverbatim + + Which is MUCH more concise and useful. + + It is also safe to copy handles - internally they are nothing more than node pointers. + @verbatim + TiXmlHandle handleCopy = handle; + @endverbatim + + What they should not be used for is iteration: + + @verbatim + int i=0; + while ( true ) + { + TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).Child( "Child", i ).ToElement(); + if ( !child ) + break; + // do something + ++i; + } + @endverbatim + + It seems reasonable, but it is in fact two embedded while loops. The Child method is + a linear walk to find the element, so this code would iterate much more than it needs + to. Instead, prefer: + + @verbatim + TiXmlElement* child = docHandle.FirstChild( "Document" ).FirstChild( "Element" ).FirstChild( "Child" ).ToElement(); + + for( child; child; child=child->NextSiblingElement() ) + { + // do something + } + @endverbatim +*/ +class TiXmlHandle +{ +public: + /// Create a handle from any node (at any depth of the tree.) This can be a null pointer. + TiXmlHandle( TiXmlNode* _node ) { this->node = _node; } + /// Copy constructor + TiXmlHandle( const TiXmlHandle& ref ) { this->node = ref.node; } + TiXmlHandle operator=( const TiXmlHandle& ref ) { if ( &ref != this ) this->node = ref.node; return *this; } + + /// Return a handle to the first child node. + TiXmlHandle FirstChild() const; + /// Return a handle to the first child node with the given name. + TiXmlHandle FirstChild( const char * value ) const; + /// Return a handle to the first child element. + TiXmlHandle FirstChildElement() const; + /// Return a handle to the first child element with the given name. + TiXmlHandle FirstChildElement( const char * value ) const; + + /** Return a handle to the "index" child with the given name. + The first child is 0, the second 1, etc. + */ + TiXmlHandle Child( const char* value, int index ) const; + /** Return a handle to the "index" child. + The first child is 0, the second 1, etc. + */ + TiXmlHandle Child( int index ) const; + /** Return a handle to the "index" child element with the given name. + The first child element is 0, the second 1, etc. Note that only TiXmlElements + are indexed: other types are not counted. + */ + TiXmlHandle ChildElement( const char* value, int index ) const; + /** Return a handle to the "index" child element. + The first child element is 0, the second 1, etc. Note that only TiXmlElements + are indexed: other types are not counted. + */ + TiXmlHandle ChildElement( int index ) const; + + #ifdef TIXML_USE_STL + TiXmlHandle FirstChild( const std::string& _value ) const { return FirstChild( _value.c_str() ); } + TiXmlHandle FirstChildElement( const std::string& _value ) const { return FirstChildElement( _value.c_str() ); } + + TiXmlHandle Child( const std::string& _value, int index ) const { return Child( _value.c_str(), index ); } + TiXmlHandle ChildElement( const std::string& _value, int index ) const { return ChildElement( _value.c_str(), index ); } + #endif + + /** Return the handle as a TiXmlNode. This may return null. + */ + TiXmlNode* ToNode() const { return node; } + /** Return the handle as a TiXmlElement. This may return null. + */ + TiXmlElement* ToElement() const { return ( ( node && node->ToElement() ) ? node->ToElement() : 0 ); } + /** Return the handle as a TiXmlText. This may return null. + */ + TiXmlText* ToText() const { return ( ( node && node->ToText() ) ? node->ToText() : 0 ); } + /** Return the handle as a TiXmlUnknown. This may return null. + */ + TiXmlUnknown* ToUnknown() const { return ( ( node && node->ToUnknown() ) ? node->ToUnknown() : 0 ); } + + /** @deprecated use ToNode. + Return the handle as a TiXmlNode. This may return null. + */ + TiXmlNode* Node() const { return ToNode(); } + /** @deprecated use ToElement. + Return the handle as a TiXmlElement. This may return null. + */ + TiXmlElement* Element() const { return ToElement(); } + /** @deprecated use ToText() + Return the handle as a TiXmlText. This may return null. + */ + TiXmlText* Text() const { return ToText(); } + /** @deprecated use ToUnknown() + Return the handle as a TiXmlUnknown. This may return null. + */ + TiXmlUnknown* Unknown() const { return ToUnknown(); } + +private: + TiXmlNode* node; +}; + + +/** Print to memory functionality. The TiXmlPrinter is useful when you need to: + + -# Print to memory (especially in non-STL mode) + -# Control formatting (line endings, etc.) + + When constructed, the TiXmlPrinter is in its default "pretty printing" mode. + Before calling Accept() you can call methods to control the printing + of the XML document. After TiXmlNode::Accept() is called, the printed document can + be accessed via the CStr(), Str(), and Size() methods. + + TiXmlPrinter uses the Visitor API. + @verbatim + TiXmlPrinter printer; + printer.SetIndent( "\t" ); + + doc.Accept( &printer ); + fprintf( stdout, "%s", printer.CStr() ); + @endverbatim +*/ +class TiXmlPrinter : public TiXmlVisitor +{ +public: + TiXmlPrinter() : depth( 0 ), simpleTextPrint( false ), + buffer(), indent( " " ), lineBreak( "\n" ) {} + + virtual bool VisitEnter( const TiXmlDocument& doc ); + virtual bool VisitExit( const TiXmlDocument& doc ); + + virtual bool VisitEnter( const TiXmlElement& element, const TiXmlAttribute* firstAttribute ); + virtual bool VisitExit( const TiXmlElement& element ); + + virtual bool Visit( const TiXmlDeclaration& declaration ); + virtual bool Visit( const TiXmlText& text ); + virtual bool Visit( const TiXmlComment& comment ); + virtual bool Visit( const TiXmlUnknown& unknown ); + + /** Set the indent characters for printing. By default 4 spaces + but tab (\t) is also useful, or null/empty string for no indentation. + */ + void SetIndent( const char* _indent ) { indent = _indent ? _indent : "" ; } + /// Query the indention string. + const char* Indent() { return indent.c_str(); } + /** Set the line breaking string. By default set to newline (\n). + Some operating systems prefer other characters, or can be + set to the null/empty string for no indenation. + */ + void SetLineBreak( const char* _lineBreak ) { lineBreak = _lineBreak ? _lineBreak : ""; } + /// Query the current line breaking string. + const char* LineBreak() { return lineBreak.c_str(); } + + /** Switch over to "stream printing" which is the most dense formatting without + linebreaks. Common when the XML is needed for network transmission. + */ + void SetStreamPrinting() { indent = ""; + lineBreak = ""; + } + /// Return the result. + const char* CStr() { return buffer.c_str(); } + /// Return the length of the result string. + size_t Size() { return buffer.size(); } + + #ifdef TIXML_USE_STL + /// Return the result. + const std::string& Str() { return buffer; } + #endif + +private: + void DoIndent() { + for( int i=0; i -#include -#include -#include "control/CtrlComponents.h" -#include "trajectory/SCurve.h" - - -class JointSpaceTraj : public Trajectory{ -public: - JointSpaceTraj(CtrlComponents *ctrlComp); - ~JointSpaceTraj(){} - - bool getJointCmd(Vec6 &q, Vec6 &qd); - bool getJointCmd(Vec6 &q, Vec6 &qd, double &gripperQ, double &gripperQd); - - void setGripper(double startQ, double endQ, double speed = M_PI); - void setJointTraj(Vec6 startQ, Vec6 endQ, double speed); - bool setJointTraj(Vec6 startQ, std::string endName, double speed); - bool setJointTraj(std::string startName, std::string endName, double speed); -private: - void _generateA345(double pathTime); - - SCurve _jointCurve; - const double ddQMax = 15.0; - const double dddQMax = 30.0; - - double _a3, _a4, _a5, _s, _sDot; -}; - +#ifndef JOINTSPACETRAJ_H +#define JOINTSPACETRAJ_H + +#include +#include +#include +#include "control/CtrlComponents.h" +#include "trajectory/SCurve.h" + + +class JointSpaceTraj : public Trajectory{ +public: + JointSpaceTraj(CtrlComponents *ctrlComp); + ~JointSpaceTraj(){} + + bool getJointCmd(Vec6 &q, Vec6 &qd); + bool getJointCmd(Vec6 &q, Vec6 &qd, double &gripperQ, double &gripperQd); + + void setGripper(double startQ, double endQ, double speed = M_PI); + void setJointTraj(Vec6 startQ, Vec6 endQ, double speed); + bool setJointTraj(Vec6 startQ, std::string endName, double speed); + bool setJointTraj(std::string startName, std::string endName, double speed); +private: + void _generateA345(double pathTime); + + SCurve _jointCurve; + const double ddQMax = 15.0; + const double dddQMax = 30.0; + + double _a3, _a4, _a5, _s, _sDot; +}; + #endif // JOINTSPACETRAJ_H \ No newline at end of file diff --git a/include/trajectory/SCurve.h b/include/trajectory/SCurve.h index cad0d30..9330785 100755 --- a/include/trajectory/SCurve.h +++ b/include/trajectory/SCurve.h @@ -1,49 +1,49 @@ -#ifndef SCURVE_H -#define SCURVE_H - -/* 归一化后的s曲线 */ - -#include - -class SCurve{ -public: - SCurve(){} - ~SCurve(){} - void setSCurve(double deltaQ, double dQMax, double ddQMax, double dddQMax); - void restart(); -/* -考虑到归一化,在实际使用时,物理量为: -加速度 = deltaQ * getDDs(); -*/ - double getDDs(); - double getDDs(double t); -/* -考虑到归一化,在实际使用时,物理量为: -速度 = deltaQ * getDs(); -*/ - double getDs(); - double getDs(double t); -/* -考虑到归一化,在实际使用时,物理量为: -位置 = deltaQ * gets(); -*/ - double gets(); - double gets(double t); - - double getT(); -private: - int _getSegment(double t); - void _setFunc(); - double _runTime(); - - bool _started = false; - double _startTime; - - double _J, _aMax, _vMax; - double _T[7]; // period - double _t[7]; // moment - double _v0, _v1; // ds at _t[0], _t[1] - double _s0, _s1, _s2, _s3, _s4, _s5, _s6; // s at _t[0], _t[1] -}; - +#ifndef SCURVE_H +#define SCURVE_H + +/* 归一化后的s曲线 */ + +#include + +class SCurve{ +public: + SCurve(){} + ~SCurve(){} + void setSCurve(double deltaQ, double dQMax, double ddQMax, double dddQMax); + void restart(); +/* +考虑到归一化,在实际使用时,物理量为: +加速度 = deltaQ * getDDs(); +*/ + double getDDs(); + double getDDs(double t); +/* +考虑到归一化,在实际使用时,物理量为: +速度 = deltaQ * getDs(); +*/ + double getDs(); + double getDs(double t); +/* +考虑到归一化,在实际使用时,物理量为: +位置 = deltaQ * gets(); +*/ + double gets(); + double gets(double t); + + double getT(); +private: + int _getSegment(double t); + void _setFunc(); + double _runTime(); + + bool _started = false; + double _startTime; + + double _J, _aMax, _vMax; + double _T[7]; // period + double _t[7]; // moment + double _v0, _v1; // ds at _t[0], _t[1] + double _s0, _s1, _s2, _s3, _s4, _s5, _s6; // s at _t[0], _t[1] +}; + #endif // SCURVE_H \ No newline at end of file diff --git a/include/trajectory/StopForTime.h b/include/trajectory/StopForTime.h index 0e435ce..7d02c99 100755 --- a/include/trajectory/StopForTime.h +++ b/include/trajectory/StopForTime.h @@ -1,17 +1,17 @@ -#ifndef STOPFORTIME_H -#define STOPFORTIME_H - -#include "trajectory/Trajectory.h" - -class StopForTime : public Trajectory{ -public: - StopForTime(CtrlComponents *ctrlComp); - ~StopForTime(){} - - bool getJointCmd(Vec6 &q, Vec6 &qd); - bool getJointCmd(Vec6 &q, Vec6 &qd, double &gripperQ, double &gripperQd); - void setStop(Vec6 stopQ, double stopTime); -private: -}; - +#ifndef STOPFORTIME_H +#define STOPFORTIME_H + +#include "trajectory/Trajectory.h" + +class StopForTime : public Trajectory{ +public: + StopForTime(CtrlComponents *ctrlComp); + ~StopForTime(){} + + bool getJointCmd(Vec6 &q, Vec6 &qd); + bool getJointCmd(Vec6 &q, Vec6 &qd, double &gripperQ, double &gripperQd); + void setStop(Vec6 stopQ, double stopTime); +private: +}; + #endif // STOPFORTIME_H \ No newline at end of file diff --git a/include/trajectory/TrajectoryManager.h b/include/trajectory/TrajectoryManager.h index 7bc364a..a4afb86 100755 --- a/include/trajectory/TrajectoryManager.h +++ b/include/trajectory/TrajectoryManager.h @@ -1,38 +1,38 @@ -#ifndef TRAJECTORY_MANAGER_H -#define TRAJECTORY_MANAGER_H - -#include -#include "control/CtrlComponents.h" -#include "trajectory/JointSpaceTraj.h" -#include "trajectory/EndLineTraj.h" -#include "trajectory/EndCircleTraj.h" -#include "trajectory/StopForTime.h" - -class TrajectoryManager{ -public: - TrajectoryManager(CtrlComponents *ctrlComp); - ~TrajectoryManager(){} - bool getJointCmd(Vec6 &q, Vec6 &qd); - bool getJointCmd(Vec6 &q, Vec6 &qd, double &gripperQ, double &gripperQd); - void addTrajectory(Trajectory* traj); - void setLoop(double backSpeed = 0.7); - void restartTraj(); - void emptyTraj(); - Vec6 getStartQ(); - Vec6 getEndQ(); - Vec6 getEndPosture(); - double getStartGripperQ(); - double getEndGripperQ(); - HomoMat getEndHomo(); - size_t size() {return _trajVec.size();} ; -private: - CtrlComponents *_ctrlComp; - JointSpaceTraj *_trajBack; - std::vector _trajVec; - int _trajID = 0; - double _jointErr = 0.05; - bool _trajCorrect = true; - bool _loop = false; -}; - +#ifndef TRAJECTORY_MANAGER_H +#define TRAJECTORY_MANAGER_H + +#include +#include "control/CtrlComponents.h" +#include "trajectory/JointSpaceTraj.h" +#include "trajectory/EndLineTraj.h" +#include "trajectory/EndCircleTraj.h" +#include "trajectory/StopForTime.h" + +class TrajectoryManager{ +public: + TrajectoryManager(CtrlComponents *ctrlComp); + ~TrajectoryManager(){} + bool getJointCmd(Vec6 &q, Vec6 &qd); + bool getJointCmd(Vec6 &q, Vec6 &qd, double &gripperQ, double &gripperQd); + void addTrajectory(Trajectory* traj); + void setLoop(double backSpeed = 0.7); + void restartTraj(); + void emptyTraj(); + Vec6 getStartQ(); + Vec6 getEndQ(); + Vec6 getEndPosture(); + double getStartGripperQ(); + double getEndGripperQ(); + HomoMat getEndHomo(); + size_t size() {return _trajVec.size();} ; +private: + CtrlComponents *_ctrlComp; + JointSpaceTraj *_trajBack; + std::vector _trajVec; + int _trajID = 0; + double _jointErr = 0.05; + bool _trajCorrect = true; + bool _loop = false; +}; + #endif // TRAJECTORY_MANAGER_H \ No newline at end of file diff --git a/lib/libZ1_ROS_Linux64.so b/lib/libZ1_ROS_x86_64.so old mode 100644 new mode 100755 similarity index 90% rename from lib/libZ1_ROS_Linux64.so rename to lib/libZ1_ROS_x86_64.so index fc463ed..5c49480 Binary files a/lib/libZ1_ROS_Linux64.so and b/lib/libZ1_ROS_x86_64.so differ diff --git a/lib/libZ1_UDP_aarch64.so b/lib/libZ1_UDP_aarch64.so new file mode 100644 index 0000000..599ef17 Binary files /dev/null and b/lib/libZ1_UDP_aarch64.so differ diff --git a/lib/libZ1_UDP_Linux64.so b/lib/libZ1_UDP_x86_64.so old mode 100644 new mode 100755 similarity index 90% rename from lib/libZ1_UDP_Linux64.so rename to lib/libZ1_UDP_x86_64.so index 87b0dd0..e06d4a0 Binary files a/lib/libZ1_UDP_Linux64.so and b/lib/libZ1_UDP_x86_64.so differ diff --git a/main.cpp b/main.cpp old mode 100755 new mode 100644