$search
00001 #ifndef WALK_INTERFACE_BINARY_HH 00002 # define WALK_INTERFACE_BINARY_HH 00003 # include <boost/filesystem/path.hpp> 00004 # include <walk_interfaces/pattern-generator.hh> 00005 00006 namespace walk 00007 { 00008 template <typename T> 00009 class BinaryReader : public T 00010 { 00011 public: 00012 typedef T patternGenerator_t; 00013 00014 explicit BinaryReader (const boost::filesystem::path& filename); 00015 00016 template <typename A> 00017 explicit BinaryReader (const boost::filesystem::path& filename, A a); 00018 template <typename A, typename B> 00019 explicit BinaryReader (const boost::filesystem::path& filename, A a, B b); 00020 template <typename A, typename B, typename C> 00021 explicit BinaryReader (const boost::filesystem::path& filename, A a, B b, C c); 00022 00023 explicit BinaryReader (std::istream& filename); 00024 ~BinaryReader (); 00025 00026 typename patternGenerator_t::Trajectory3d& leftFootTrajectory () 00027 { 00028 return this->getLeftFootTrajectory (); 00029 } 00030 00031 typename patternGenerator_t::Trajectory3d& rightFootTrajectory () 00032 { 00033 return this->getRightFootTrajectory (); 00034 } 00035 00036 typename patternGenerator_t::TrajectoryV2d& zmpTrajectory () 00037 { 00038 return this->getZmpTrajectory (); 00039 } 00040 00041 typename patternGenerator_t::TrajectoryV3d& centerOfMassTrajectory () 00042 { 00043 return this->getCenterOfMassTrajectory (); 00044 } 00045 00046 typename patternGenerator_t::TrajectoryNd& postureTrajectory () 00047 { 00048 return this->getPostureTrajectory (); 00049 } 00050 00051 typename patternGenerator_t::Trajectory3d& leftHandTrajectory () 00052 { 00053 return this->getLeftHandTrajectory (); 00054 } 00055 00056 typename patternGenerator_t::Trajectory3d& rightHandTrajectory () 00057 { 00058 return this->getRightHandTrajectory (); 00059 } 00060 00061 00062 HomogeneousMatrix3d& initialLeftFootPosition () 00063 { 00064 return this->getInitialLeftFootPosition (); 00065 } 00066 00067 HomogeneousMatrix3d& initialRightFootPosition () 00068 { 00069 return this->getInitialRightFootPosition (); 00070 } 00071 00072 Vector3d& initialCenterOfMassPosition () 00073 { 00074 return this->getInitialCenterOfMassPosition (); 00075 } 00076 00077 Posture& initialPosture () 00078 { 00079 return this->getInitialPosture (); 00080 } 00081 00082 HomogeneousMatrix3d& initialLeftHandPosition () 00083 { 00084 return this->getInitialLeftHandPosition (); 00085 } 00086 00087 HomogeneousMatrix3d& initialRightHandPosition () 00088 { 00089 return this->getInitialRightHandPosition (); 00090 } 00091 00092 00093 HomogeneousMatrix3d& finalLeftFootPosition () 00094 { 00095 return this->getFinalLeftFootPosition (); 00096 } 00097 00098 HomogeneousMatrix3d& finalRightFootPosition () 00099 { 00100 return this->getFinalRightFootPosition (); 00101 } 00102 00103 Vector3d& finalCenterOfMassPosition () 00104 { 00105 return this->getFinalCenterOfMassPosition (); 00106 } 00107 00108 Posture& finalPosture () 00109 { 00110 return this->getFinalPosture (); 00111 } 00112 00113 HomogeneousMatrix3d& finalLeftHandPosition () 00114 { 00115 return this->getFinalLeftHandPosition (); 00116 } 00117 00118 HomogeneousMatrix3d& finalRightHandPosition () 00119 { 00120 return this->getFinalRightHandPosition (); 00121 } 00122 00123 00124 virtual void computeTrajectories () 00125 {} 00126 00127 protected: 00128 void load (const boost::filesystem::path& filename); 00129 void load (std::istream& stream); 00130 public: 00131 EIGEN_MAKE_ALIGNED_OPERATOR_NEW; 00132 }; 00133 00134 struct BinaryReaderHelper 00135 { 00136 BinaryReaderHelper (std::istream& stream) 00137 : stream (stream) 00138 {} 00139 std::istream& stream; 00140 }; 00141 00142 template <typename T> 00143 BinaryReaderHelper& 00144 operator>> (BinaryReaderHelper& helper, BinaryReader<T>& pg); 00145 00146 00147 00148 template <typename T> 00149 class BinaryWriter 00150 { 00151 public: 00152 typedef T patternGenerator_t; 00153 00154 explicit BinaryWriter (const patternGenerator_t& pg); 00155 ~BinaryWriter (); 00156 00157 void write (const std::string& filename) const; 00158 void write (boost::filesystem::path& filename) const; 00159 void write (std::ostream& stream) const; 00160 00161 private: 00163 const patternGenerator_t& patternGenerator_; 00164 }; 00165 00166 struct BinaryWriterHelper 00167 { 00168 BinaryWriterHelper (std::ostream& s) 00169 : stream (s) 00170 {} 00171 std::ostream& stream; 00172 }; 00173 00174 template <typename T> 00175 BinaryWriterHelper& 00176 operator<< (BinaryWriterHelper& helper, const PatternGenerator<T>& pg); 00177 00178 } // end of namespace walk. 00179 00180 # include <walk_interfaces/binary.hxx> 00181 #endif //! WALK_INTERFACE_BINARY_HH