TinyURDF 1.0.0
Loading...
Searching...
No Matches
joint.h
Go to the documentation of this file.
1#ifndef INCLUDE_TINYURDF_CORE_JOINT_H_
2#define INCLUDE_TINYURDF_CORE_JOINT_H_
3
4// Copyright 2025 Wissem CHIHA
5
6#include <loguru/loguru.hpp>
7#include <memory>
8#include <string>
9#include <vector>
10
11#include "common/object_base.h"
13#include "core/joint_dynamics.h"
14#include "core/joint_limits.h"
15#include "core/joint_mimic.h"
16#include "core/joint_safety.h"
17#include "core/pose.h"
18#include "utility/utils.h"
19
20class Joint : public ObjectBase
21{
22 public:
23 enum class Type
24 {
25 UNKNOWN,
30 PLANAR,
31 FIXED,
33 };
34 Joint();
35 Joint(const Joint& rhs);
36 Joint(Joint&& rhs) noexcept;
37 void clear() override;
38 bool isA(const char* name) const override;
39 std::string toString() const override;
40 bool empty() const override;
41 const char* getTypename() const override;
42 void setDynamics(const std::shared_ptr<JointDynamics> d);
43 void setLimits(const std::shared_ptr<JointLimits> l);
44 void setSafety(const std::shared_ptr<JointSafety> s);
45 void setCalibration(const std::shared_ptr<JointCalibration> c);
46 void setMimic(const std::shared_ptr<JointMimic> m);
47 void setName(const std::string& name_);
48 void setType(const Type& t_);
49 void setType(const char* c_);
50 void setAxis(double x, double y, double z);
51 std::string getName() const;
52 void pushBackChild(const std::string lk);
53 void pushBackParent(const std::string lk);
54 void pushBackTransform(const std::shared_ptr<Pose> t);
55 bool isChild(const char* name) const;
56 bool isParent(const char* name) const;
57 std::vector<std::shared_ptr<Pose>> getTransform() const;
58 std::vector<std::string> getChild() const;
59 std::vector<std::string> getParent() const;
60 Vec3 getAxis() const;
61
62 private:
63 Type type;
64 std::string name;
65 Vec3 axis;
66 std::vector<std::string> child;
67 std::vector<std::string> parent;
68 std::vector<std::shared_ptr<Pose>> transform;
69 std::shared_ptr<JointDynamics> dynamics;
70 std::shared_ptr<JointLimits> limits;
71 std::shared_ptr<JointSafety> safety;
72 std::shared_ptr<JointCalibration> calibration;
73 std::shared_ptr<JointMimic> mimic;
74};
75#endif // INCLUDE_TINYURDF_CORE_JOINT_H
Definition joint.h:21
std::string getName() const
Definition joint.cc:156
void setMimic(const std::shared_ptr< JointMimic > m)
Definition joint.cc:114
std::vector< std::shared_ptr< Pose > > getTransform() const
Definition joint.cc:185
void setType(const Type &t_)
Definition joint.cc:126
std::string toString() const override
Definition joint.cc:47
void clear() override
Definition joint.cc:32
void setSafety(const std::shared_ptr< JointSafety > s)
Definition joint.cc:104
void pushBackChild(const std::string lk)
Definition joint.cc:161
void setCalibration(const std::shared_ptr< JointCalibration > c)
Definition joint.cc:109
std::vector< std::string > getChild() const
Definition joint.cc:190
bool empty() const override
Definition joint.cc:84
Joint()
Definition joint.cc:3
Vec3 getAxis() const
Definition joint.cc:200
void setLimits(const std::shared_ptr< JointLimits > l)
Definition joint.cc:99
Type
Definition joint.h:24
void setAxis(double x, double y, double z)
Definition joint.cc:151
void setName(const std::string &name_)
Definition joint.cc:119
void pushBackTransform(const std::shared_ptr< Pose > t)
Definition joint.cc:171
const char * getTypename() const override
Definition joint.cc:89
void pushBackParent(const std::string lk)
Definition joint.cc:166
bool isChild(const char *name) const
Definition joint.cc:175
std::vector< std::string > getParent() const
Definition joint.cc:195
bool isA(const char *name) const override
Definition joint.cc:42
void setDynamics(const std::shared_ptr< JointDynamics > d)
Definition joint.cc:94
bool isParent(const char *name) const
Definition joint.cc:180
Definition object_base.h:9
Eigen::Matrix< double, 3, 1 > Vec3
Base struct for 3D position vectors.
Definition utils.h:17