dyn::Robot
rb::dyn::Robot is the main rigid-body model type in the SDK. It exposes the
kinematics and dynamics computations used by model-based control and offline
analysis tools.
Header
Header |
#include <rby1-sdk/dynamics/robot.h>
|
Declaration
Namespace |
rb::dyn
|
Kind |
class template
|
Primary role |
Own a robot model and compute forward kinematics, Jacobians, center of
mass, gravity terms, mass matrices, and inverse dynamics. |
Public Member Functions
Method group |
Purpose |
Notes |
Robot(...) and CountJoints(...)
|
Construct a model and inspect link-tree size. |
CountJoints(...) is the main static helper.
|
ComputeForwardKinematics(...) and differential variants
|
Update link transforms and motion derivatives in a state object. |
Use before Jacobian or body-velocity queries. |
ComputeBodyJacobian(...) and ComputeSpaceJacobian(...)
|
Compute task-space Jacobians between links. |
Common in controller and estimator code. |
ComputeCenterOfMass(...) and ComputeCenterOfMassJacobian(...)
|
Compute COM position and Jacobians. |
Supports whole robot or selected target links. |
ComputeGravityTerm(...), ComputeMassMatrix(...),
ComputeInverseDynamics(...)
|
Compute the main dynamics terms. |
These are the standard model-based control outputs. |
ComputeMass(...) and ComputeReflectiveInertia(...)
|
Inspect local reflected mass and inertia quantities. |
Useful for analysis and tuning. |
ComputeMobility* helpers
|
Map planar mobility commands through the model. |
Relevant for mobile-base variants. |
Detailed Reference
-
template<int DOF>
class Robot
Public Types
-
template<typename T, int N>
using ContainerType = typename std::conditional_t<(N > 0), std::array<T, (unsigned int)N>, std::vector<T>>
Public Functions
-
inline explicit Robot(const RobotConfiguration &robot_configuration)
-
inline void Compute2ndDiffForwardKinematics(std::shared_ptr<State<DOF>> state)
-
inline Eigen::Matrix<double, 6, DOF> ComputeBodyJacobian(std::shared_ptr<State<DOF>> state, unsigned int from, unsigned int to)
-
inline math::se3v::MatrixType ComputeBodyVelocity(std::shared_ptr<State<DOF>> state, unsigned int from, unsigned int to)
-
inline Eigen::Vector3d ComputeCenterOfMass(std::shared_ptr<State<DOF>> state, unsigned int ref_link)
-
inline Eigen::Vector3d ComputeCenterOfMass(std::shared_ptr<State<DOF>> state, unsigned int ref_link, const std::vector<unsigned int> &target_links)
-
inline Eigen::Vector3d ComputeCenterOfMass(std::shared_ptr<State<DOF>> state, unsigned int ref_link, unsigned int target_link)
-
inline Eigen::Matrix<double, 3, DOF> ComputeCenterOfMassJacobian(std::shared_ptr<State<DOF>> state, unsigned int ref_link)
-
inline Eigen::Matrix<double, 3, DOF> ComputeCenterOfMassJacobian(std::shared_ptr<State<DOF>> state, unsigned int ref_link, unsigned int target_link)
-
inline void ComputeDiffForwardKinematics(std::shared_ptr<State<DOF>> state)
-
inline void ComputeForwardKinematics(std::shared_ptr<State<DOF>> state)
-
inline Eigen::Vector<double, DOF> ComputeGravityTerm(std::shared_ptr<State<DOF>> state)
-
inline void ComputeInverseDynamics(std::shared_ptr<State<DOF>> state)
-
inline double ComputeMass(std::shared_ptr<State<DOF>> state, unsigned int target_link)
-
inline Eigen::Matrix<double, DOF, DOF> ComputeMassMatrix(std::shared_ptr<State<DOF>> state)
-
inline math::se2v::MatrixType ComputeMobilityDiffKinematics(std::shared_ptr<State<DOF>> state)
-
inline void ComputeMobilityInverseDiffKinematics(std::shared_ptr<State<DOF>> state, const Eigen::Vector2d &linear_velocity, double angular_velocity)
-
inline void ComputeMobilityInverseDiffKinematics(std::shared_ptr<State<DOF>> state, const math::se2v::MatrixType &body_velocity)
-
inline Eigen::Matrix<double, 6, 6> ComputeReflectiveInertia(std::shared_ptr<State<DOF>> state, unsigned int from, unsigned int to)
-
inline Eigen::Matrix<double, 6, DOF> ComputeSpaceJacobian(std::shared_ptr<State<DOF>> state, unsigned int from, unsigned int to)
-
inline Inertial::MatrixType ComputeTotalInertial(std::shared_ptr<State<DOF>> state, unsigned int ref_link)
Compute total inertial of robot
- Parameters:
-
- Returns:
-
-
inline math::SE3::MatrixType ComputeTransformation(std::shared_ptr<State<DOF>> state, unsigned int from, unsigned int to)
-
inline std::vector<CollisionResult> DetectCollisionsOrNearestLinks(std::shared_ptr<State<DOF>> state, int collision_threshold = 0)
-
inline std::shared_ptr<Link> GetBase()
-
inline std::shared_ptr<const Link> GetBase() const
-
inline int GetDOF() const
-
inline std::vector<std::string> GetJointNames() const
-
inline Eigen::Vector<double, DOF> GetJointProperty(const std::shared_ptr<State<DOF>> &state, const std::function<double(std::shared_ptr<Joint>)> &getter)
-
inline Eigen::Vector<double, DOF> GetLimitQddotLower(const std::shared_ptr<State<DOF>> &state)
-
inline Eigen::Vector<double, DOF> GetLimitQddotUpper(const std::shared_ptr<State<DOF>> &state)
-
inline Eigen::Vector<double, DOF> GetLimitQdotLower(const std::shared_ptr<State<DOF>> &state)
-
inline Eigen::Vector<double, DOF> GetLimitQdotUpper(const std::shared_ptr<State<DOF>> &state)
-
inline Eigen::Vector<double, DOF> GetLimitQLower(const std::shared_ptr<State<DOF>> &state)
-
inline Eigen::Vector<double, DOF> GetLimitQUpper(const std::shared_ptr<State<DOF>> &state)
-
inline Eigen::Vector<double, DOF> GetLimitTorque(const std::shared_ptr<State<DOF>> &state)
-
inline std::shared_ptr<Link> GetLink(const std::string &name) const
-
inline std::shared_ptr<Link> GetLink(std::shared_ptr<State<DOF>> state, int index) const
-
inline std::vector<std::string> GetLinkNames() const
-
inline int GetNumberOfJoints() const
-
template<typename LinkContainer = std::vector<std::string>, typename JointContainer = std::vector<std::string>>
inline std::shared_ptr<State<DOF>> MakeState(const LinkContainer &link_names, const JointContainer &joint_names)
Public Static Functions
-
static inline int CountJoints(const std::shared_ptr<Link> &base_link, bool include_fixed = false)
-
struct Joint_
Public Members
-
int child_link_idx = {}
-
std::shared_ptr<Joint> joint = {nullptr}
-
int parent_link_idx = {}
-
math::se3v::MatrixType S = {math::se3v::MatrixType::Zero()}
-
struct Link_
Public Functions
-
inline int AddLink(const std::shared_ptr<Link> &link, const math::SE3::MatrixType &M_wrt_p)
-
inline void SetBaseLink(const std::shared_ptr<Link> &link, const math::SE3::MatrixType &T)
-
struct SubLink_
-
-
struct LinkIdx_
Public Members
-
int link_idx
-
int sub_link_idx
Related Types
Examples