$search
00001 #ifndef WALK_INTERFACE_YAML_HH 00002 # define WALK_INTERFACE_YAML_HH 00003 # include <boost/filesystem/path.hpp> 00004 # include <walk_interfaces/pattern-generator.hh> 00005 00006 # include "yaml-cpp/yaml.h" 00007 00008 namespace walk 00009 { 00011 template <typename T> 00012 void 00013 operator>> (const YAML::Node& node, PatternGenerator<T>& pg); 00014 00026 template <typename T> 00027 class YamlReader : public T 00028 { 00029 public: 00031 typedef T patternGenerator_t; 00032 00035 00040 explicit YamlReader (const boost::filesystem::path& filename); 00041 00045 explicit YamlReader (std::istream& stream); 00046 00047 template <typename A> 00048 explicit YamlReader (const boost::filesystem::path& filename, A a); 00049 template <typename A, typename B> 00050 explicit YamlReader (const boost::filesystem::path& filename, A a, B b); 00051 template <typename A, typename B, typename C> 00052 explicit YamlReader (const boost::filesystem::path& filename, A a, B b, C c); 00053 00054 template <typename A> 00055 explicit YamlReader (std::istream& stream, A a); 00056 template <typename A, typename B> 00057 explicit YamlReader (std::istream& stream, A a, B b); 00058 template <typename A, typename B, typename C> 00059 explicit YamlReader (std::istream& stream, A a, B b, C c); 00060 00061 00062 00064 ~YamlReader (); 00065 00067 00068 00069 typename patternGenerator_t::Trajectory3d& leftFootTrajectory () 00070 { 00071 return this->getLeftFootTrajectory (); 00072 } 00073 00074 typename patternGenerator_t::Trajectory3d& rightFootTrajectory () 00075 { 00076 return this->getRightFootTrajectory (); 00077 } 00078 00079 typename patternGenerator_t::TrajectoryV2d& zmpTrajectory () 00080 { 00081 return this->getZmpTrajectory (); 00082 } 00083 00084 typename patternGenerator_t::TrajectoryV3d& centerOfMassTrajectory () 00085 { 00086 return this->getCenterOfMassTrajectory (); 00087 } 00088 00089 typename patternGenerator_t::TrajectoryNd& postureTrajectory () 00090 { 00091 return this->getPostureTrajectory (); 00092 } 00093 00094 typename patternGenerator_t::Trajectory3d& leftHandTrajectory () 00095 { 00096 return this->getLeftHandTrajectory (); 00097 } 00098 00099 typename patternGenerator_t::Trajectory3d& rightHandTrajectory () 00100 { 00101 return this->getRightHandTrajectory (); 00102 } 00103 00104 00105 HomogeneousMatrix3d& initialLeftFootPosition () 00106 { 00107 return this->getInitialLeftFootPosition (); 00108 } 00109 00110 HomogeneousMatrix3d& initialRightFootPosition () 00111 { 00112 return this->getInitialRightFootPosition (); 00113 } 00114 00115 Vector3d& initialCenterOfMassPosition () 00116 { 00117 return this->getInitialCenterOfMassPosition (); 00118 } 00119 00120 Posture& initialPosture () 00121 { 00122 return this->getInitialPosture (); 00123 } 00124 00125 HomogeneousMatrix3d& initialLeftHandPosition () 00126 { 00127 return this->getInitialLeftHandPosition (); 00128 } 00129 00130 HomogeneousMatrix3d& initialRightHandPosition () 00131 { 00132 return this->getInitialRightHandPosition (); 00133 } 00134 00135 00136 HomogeneousMatrix3d& finalLeftFootPosition () 00137 { 00138 return this->getFinalLeftFootPosition (); 00139 } 00140 00141 HomogeneousMatrix3d& finalRightFootPosition () 00142 { 00143 return this->getFinalRightFootPosition (); 00144 } 00145 00146 Vector3d& finalCenterOfMassPosition () 00147 { 00148 return this->getFinalCenterOfMassPosition (); 00149 } 00150 00151 Posture& finalPosture () 00152 { 00153 return this->getFinalPosture (); 00154 } 00155 00156 HomogeneousMatrix3d& finalLeftHandPosition () 00157 { 00158 return this->getFinalLeftHandPosition (); 00159 } 00160 00161 HomogeneousMatrix3d& finalRightHandPosition () 00162 { 00163 return this->getFinalRightHandPosition (); 00164 } 00165 00166 virtual void computeTrajectories () 00167 {} 00168 00169 protected: 00171 void load (const boost::filesystem::path& filename); 00173 void load (std::istream& stream); 00174 public: 00175 EIGEN_MAKE_ALIGNED_OPERATOR_NEW; 00176 }; 00177 00191 template <typename T> 00192 class YamlWriter 00193 { 00194 public: 00196 typedef T patternGenerator_t; 00197 00200 00204 explicit YamlWriter (const patternGenerator_t& pg); 00205 00207 ~YamlWriter (); 00208 00210 00214 void write (const std::string& filename) const; 00215 00219 void write (boost::filesystem::path& filename) const; 00220 00225 void write (std::ostream& stream) const; 00226 00227 private: 00229 const patternGenerator_t& patternGenerator_; 00230 }; 00231 00232 } // end of namespace walk. 00233 00234 # include <walk_interfaces/yaml.hxx> 00235 #endif //! WALK_INTERFACE_YAML_HH