| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_USER_USER_UTIL_H_ |
| | #define MUJOCO_SRC_USER_USER_UTIL_H_ |
| |
|
| | #include <algorithm> |
| | #include <cstddef> |
| | #include <cstdint> |
| | #include <optional> |
| | #include <string> |
| | #include <string_view> |
| | #include <vector> |
| |
|
| | const double mjEPS = 1E-14; |
| | const double mjMINMASS = 1E-6; |
| |
|
| | |
| | bool mjuu_defined(double num); |
| |
|
| | |
| | |
| | int mjuu_matadr(int g1, int g2, int n); |
| |
|
| | |
| | void mjuu_setvec(double* dest, double x, double y, double z, double w); |
| | void mjuu_setvec(float* dest, double x, double y, double z, double w); |
| |
|
| | |
| | void mjuu_setvec(double* dest, double x, double y, double z); |
| | void mjuu_setvec(float* dest, double x, double y, double z); |
| |
|
| | |
| | void mjuu_setvec(double* dest, double x, double y); |
| |
|
| | |
| | template <class T1, class T2> |
| | void mjuu_copyvec(T1* dest, const T2* src, int n) { |
| | std::copy(src, src + n, dest); |
| | } |
| |
|
| | |
| | void mjuu_addtovec(double* dest, const double* src, int n); |
| |
|
| | |
| | void mjuu_zerovec(double* dest, int n); |
| |
|
| | |
| | void mjuu_zerovec(float* dest, int n); |
| |
|
| | |
| | double mjuu_dot3(const double* a, const double* b); |
| |
|
| | |
| | double mjuu_dist3(const double* a, const double* b); |
| |
|
| | |
| | double mjuu_L1(const double* a, const double* b, int n); |
| |
|
| | |
| | |
| | double mjuu_normvec(double* vec, int n); |
| | float mjuu_normvec(float* vec, int n); |
| |
|
| | |
| | void mjuu_quat2mat(double* res, const double* quat); |
| |
|
| | |
| | void mjuu_mulquat(double* res, const double* qa, const double* qb); |
| |
|
| | |
| | void mjuu_mulvecmat(double* res, const double* vec, const double* mat); |
| |
|
| | |
| | void mjuu_mulvecmatT(double* res, const double* vec, const double* mat); |
| |
|
| | |
| | void mjuu_mulRMRT(double* res, const double* R, const double* M); |
| |
|
| | |
| | void mjuu_mulmat(double* res, const double* A, const double* B); |
| |
|
| | |
| | void mjuu_transposemat(double* res, const double* mat); |
| |
|
| | |
| | void mjuu_localaxis(double* al, const double* ag, const double* quat); |
| |
|
| | |
| | void mjuu_localpos(double* pl, const double* pg, const double* pos, const double* quat); |
| |
|
| | |
| | void mjuu_localquat(double* local, const double* child, const double* parent); |
| |
|
| | |
| | void mjuu_crossvec(double* a, const double* b, const double* c); |
| |
|
| | |
| | template<typename T> double mjuu_makenormal(double* normal, const T a[3], |
| | const T b[3], const T c[3]); |
| |
|
| | |
| | void mjuu_z2quat(double* quat, const double* vec); |
| |
|
| | |
| | void mjuu_frame2quat(double* quat, const double* x, const double* y, const double* z); |
| |
|
| | |
| | void mjuu_frameinvert(double newpos[3], double newquat[4], |
| | const double oldpos[3], const double oldquat[4]); |
| |
|
| | |
| | void mjuu_frameaccum(double pos[3], double quat[4], |
| | const double childpos[3], const double childquat[4]); |
| |
|
| | |
| | void mjuu_frameaccumChild(const double pos[3], const double quat[4], |
| | double childpos[3], double childquat[4]); |
| |
|
| | |
| | void mjuu_frameaccuminv(double pos[3], double quat[4], |
| | const double childpos[3], const double childquat[4]); |
| |
|
| | |
| | void mjuu_globalinertia(double* global, const double* local, const double* quat); |
| |
|
| | |
| | void mjuu_offcenter(double* res, double mass, const double* vec); |
| |
|
| | |
| | void mjuu_visccoef(double* visccoef, double mass, const double* inertia, double scl=1); |
| |
|
| | |
| | void mjuu_rotVecQuat(double res[3], const double vec[3], const double quat[4]); |
| |
|
| | |
| | double mjuu_updateFrame(double quat[4], double normal[3], const double edge[3], |
| | const double tprv[3], const double tnxt[3], int first); |
| |
|
| | |
| | int mjuu_eig3(double eigval[3], double eigvec[9], double quat[4], const double mat[9]); |
| |
|
| | |
| | void mjuu_trnVecPose(double res[3], const double pos[3], const double quat[4], const double vec[3]); |
| |
|
| | |
| | const char* mjuu_fullInertia(double quat[4], double inertia[3], const double fullinertia[6]); |
| |
|
| | namespace mujoco::user { |
| |
|
| | |
| | class FilePath { |
| | public: |
| | FilePath() = default; |
| | explicit FilePath(const std::string& str) : path_(PathReduce(str)) {} |
| | explicit FilePath(const char* str) { path_ = PathReduce(str); } |
| | FilePath(const std::string& str1, const std::string& str2) { |
| | path_ = PathReduce(Combine(str1, str2)); |
| | } |
| | FilePath(FilePath&& other) = default; |
| | FilePath& operator=(FilePath&& other) = default; |
| | FilePath(const FilePath&) = default; |
| | FilePath& operator=(const FilePath&) = default; |
| |
|
| | |
| | bool IsAbs() const { return !AbsPrefix(path_).empty(); } |
| |
|
| | |
| | |
| | std::string AbsPrefix() const { return AbsPrefix(path_); } |
| |
|
| | |
| | const std::string& Str() const { return path_; } |
| |
|
| | |
| | |
| | std::string StrLower() const; |
| |
|
| | |
| | std::string Ext() const; |
| |
|
| | |
| | FilePath operator+(const FilePath& path) const; |
| |
|
| | |
| | FilePath StripExt() const; |
| |
|
| | |
| | FilePath StripPath() const; |
| |
|
| | |
| | FilePath Lower() const { return FilePathFast(StrLower()); } |
| |
|
| | |
| | std::size_t size() const { return path_.size(); } |
| | const char* c_str() const { return path_.c_str(); } |
| | bool empty() const { return path_.empty(); } |
| | char operator[](int i) const { return path_[i]; } |
| |
|
| | private: |
| | static std::string AbsPrefix(const std::string& str); |
| | static std::string PathReduce(const std::string& str); |
| | static bool IsSeparator(char c) { |
| | return c == '/' || c == '\\'; |
| | } |
| | static std::string Combine(const std::string& s1, const std::string& s2); |
| |
|
| | |
| | static FilePath FilePathFast(const std::string& str) { |
| | FilePath path; |
| | path.path_ = str; |
| | return path; |
| | } |
| |
|
| | static FilePath FilePathFast(std::string&& str) { |
| | FilePath path; |
| | path.path_ = str; |
| | return path; |
| | } |
| |
|
| | std::string path_; |
| | }; |
| |
|
| | |
| | std::vector<uint8_t> FileToMemory(const char* filename); |
| |
|
| | |
| | template<typename T> std::string VectorToString(const std::vector<T>& v); |
| |
|
| | |
| | template<typename T> std::vector<T> StringToVector(char *cs); |
| | template<typename T> std::vector<T> StringToVector(const std::string& s); |
| |
|
| | } |
| |
|
| | |
| | std::string mjuu_strippath(std::string filename); |
| |
|
| | |
| | std::string mjuu_stripext(std::string filename); |
| |
|
| | |
| | std::string mjuu_getext(std::string_view filename); |
| |
|
| | |
| | bool mjuu_isabspath(std::string path); |
| |
|
| | |
| | std::string mjuu_combinePaths(const std::string& path1, const std::string& path2); |
| | std::string mjuu_combinePaths(const std::string& path1, const std::string& path2, |
| | const std::string& path3); |
| |
|
| | |
| | std::optional<std::string_view> mjuu_parseContentTypeAttrType(std::string_view text); |
| |
|
| | |
| | std::optional<std::string_view> mjuu_parseContentTypeAttrSubtype(std::string_view text); |
| |
|
| | |
| | std::string mjuu_extToContentType(std::string_view filename); |
| |
|
| | |
| | int mjuu_dirnamelen(const char* path); |
| |
|
| | #endif |
| |
|