Go to the documentation of this file.00001 #ifndef __PROJECT_H__
00002 #define __PROJECT_H__
00003 
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <hrpUtil/Eigen3d.h>
00008 
00009 class CollisionPairItem {
00010 public:
00011     std::string objectName1;
00012     std::string objectName2;
00013     std::string jointName1;
00014     std::string jointName2;
00015     double slidingFriction;
00016     double staticFriction;
00017     double cullingThresh;
00018     double restitution;
00019     std::string sprintDamperModel;
00020 
00021     CollisionPairItem() {
00022         jointName1 = "";
00023         jointName2 = "";
00024         slidingFriction = 0.5;
00025         staticFriction = 0.5;
00026         cullingThresh = 0.01;
00027         restitution = 0.0;
00028         sprintDamperModel = "false";
00029     }
00030 };
00031 
00032 class JointItem {
00033 public:
00034     JointItem() : 
00035         angle(0), isHighGain(false), NumOfAABB(0), 
00036         translation(hrp::Vector3::Zero()), 
00037         rotation(hrp::Matrix33::Identity()),
00038         linearVelocity(hrp::Vector3::Zero()),
00039         angularVelocity(hrp::Vector3::Zero()){}
00040     double angle;
00041     bool isHighGain;
00042     int NumOfAABB;
00043     hrp::Vector3 translation;
00044     hrp::Matrix33 rotation;
00045     hrp::Vector3 linearVelocity, angularVelocity;
00046     std::string collisionShape;
00047 };
00048 
00049 class ExtraJointItem {
00050 public:
00051     ExtraJointItem() :
00052         jointAxis(0,0,1), 
00053         link1LocalPos(0,0,0), link2LocalPos(0,0,0), 
00054         jointType("xyz"){}
00055     hrp::Vector3 jointAxis;
00056     hrp::Vector3 link1LocalPos, link2LocalPos;
00057     std::string object1Name, object2Name, link1Name, link2Name, jointType;
00058 };
00059 
00060 class ModelItem {
00061 public:
00062     std::string url;
00063     std::map<std::string,JointItem> joint;
00064     std::string rtcName;
00065     std::vector<std::string > inports;
00066     std::vector<std::string > outports;
00067 };
00068 
00069 class RTSItem {
00070 public:
00071     class rtc{
00072     public:
00073         rtc() : period(0.0){}
00074         std::string name;
00075         std::string path;
00076         double period;
00077         std::vector<std::pair<std::string, std::string> > configuration;
00078     };
00079     std::map<std::string, rtc> components;
00080     std::vector<std::pair<std::string, std::string> > connections;
00081 };
00082 
00083 class RobotHardwareClientView
00084 {
00085 public:
00086     RobotHardwareClientView() : 
00087         hostname("localhost"), RobotHardwareName("RobotHardware0"),
00088         StateHolderName("StateHolder0"), port(2809), interval(100){}
00089     std::string hostname, RobotHardwareName, StateHolderName;
00090     int port, interval;
00091 };
00092 
00093 class ThreeDView
00094 {
00095 public:
00096     ThreeDView();
00097     bool showScale, showCoM, showCoMonFloor, showCollision;  
00098     double T[16];
00099 };
00100 
00101 class Project{
00102 public:
00103     Project();
00104     bool parse(const std::string &filename);
00105     double timeStep() { return m_timeStep; }
00106     double totalTime() { return m_totalTime; }
00107     void totalTime(double time) { m_totalTime = time; }
00108     double logTimeStep() { return m_logTimeStep; }
00109     double gravity() { return m_gravity; }
00110     bool isEuler() { return m_isEuler; }
00111     bool kinematicsOnly() { return m_kinematicsOnly; }
00112     bool realTime() { return m_realTime; }
00113     void realTime(bool flag) { m_realTime = flag; }
00114     std::map<std::string, ModelItem>& models(){ return m_models; }
00115     std::vector<CollisionPairItem>& collisionPairs() { return m_collisionPairs; }
00116     std::vector<ExtraJointItem>& extraJoints() { return m_extraJoints; }
00117     RTSItem &RTS() { return m_rts; }
00118     RobotHardwareClientView &RobotHardwareClient() { return m_rhview; }
00119     ThreeDView &view() { return m_3dview; }
00120 private:
00121     double m_timeStep, m_logTimeStep;
00122     double m_totalTime;
00123     double m_gravity;
00124     bool m_isEuler;
00125     bool m_kinematicsOnly;
00126     bool m_realTime;
00127     std::map<std::string, ModelItem> m_models;
00128     std::vector<CollisionPairItem> m_collisionPairs;
00129     std::vector<ExtraJointItem> m_extraJoints;
00130     RTSItem m_rts;
00131     RobotHardwareClientView m_rhview;
00132     ThreeDView m_3dview;
00133 };
00134 #endif