libxr 1.0
Want to be the best embedded framework
|
机器人起始点(StartPoint)类,继承自 Object。 StartPoint class representing the base or root of a robotic kinematic chain, inheriting from Object. More...
#include <kinematic.hpp>
Public Member Functions | |
StartPoint (Inertia< Scalar > &inertia) | |
构造 StartPoint 物体对象。 Constructs a StartPoint object. | |
void | CalcForward () |
计算当前状态的前向运动学(FK)。 Computes forward kinematics (FK) for the current state. | |
void | CalcTargetForward () |
计算目标状态的前向运动学(FK)。 Computes forward kinematics (FK) for the target state. | |
void | CalcInertia () |
计算机器人系统的惯性分布。 Computes the inertia distribution of the robotic system. | |
void | CalcCenterOfMass () |
计算机器人系统的质心。 Computes the center of mass (CoM) of the robotic system. | |
![]() | |
Object (Inertia< Scalar > &inertia) | |
使用惯性参数构造 Object 对象。 Constructs an Object using inertia parameters. | |
void | SetPosition (const Position< Scalar > &pos) |
设置物体的位置信息。 Sets the position of the object. | |
void | SetQuaternion (const Quaternion< Scalar > &quat) |
设置物体的旋转信息(四元数表示)。 Sets the rotation of the object using a quaternion. | |
virtual void | CalcBackward () |
Static Public Member Functions | |
static ErrorCode | InertiaForeachFunLoopStart (Joint< Scalar > *joint, Joint< Scalar > *parent) |
计算起始点惯性(首次遍历)。 Computes the inertia of the start point (first traversal). | |
static ErrorCode | InertiaForeachFunLoop (Joint< Scalar > *joint, Joint< Scalar > *parent) |
计算机器人系统的惯性(后续遍历)。 Computes the inertia of the robotic system (subsequent traversal). | |
static ErrorCode | ForwardForeachFunLoop (Joint< Scalar > *joint, StartPoint< Scalar > &start) |
计算当前状态的前向运动学(FK)。 Computes forward kinematics (FK) for the current state. | |
static ErrorCode | TargetForwardForeachFunLoop (Joint< Scalar > *joint, StartPoint< Scalar > &start) |
计算目标状态的前向运动学(FK)。 Computes forward kinematics (FK) for the target state. | |
static ErrorCode | CenterOfMassForeachFunLoop (Joint< Scalar > *joint, StartPoint< Scalar > &start) |
计算系统的质心。 Computes the center of mass of the system. | |
Data Fields | |
CenterOfMass< Scalar > | cog |
机器人质心。 The center of mass of the robot. | |
![]() | |
List | joints |
物体的关节列表。 List of joints associated with the object. | |
Joint< Scalar > * | parent = nullptr |
指向父关节的指针。 Pointer to the parent joint. | |
Param | param_ |
物体参数。 Object parameters. | |
Runtime | runtime_ |
物体运行时状态。 Object runtime data. | |
Additional Inherited Members | |
![]() | |
typedef List::Node< Joint< Scalar > * > | Link |
关节链接类型。 Type for linking joints. | |
机器人起始点(StartPoint)类,继承自 Object。 StartPoint class representing the base or root of a robotic kinematic chain, inheriting from Object.
该类作为运动学链的起始点,负责计算前向运动学、逆向运动学、 质心计算以及惯性计算等关键功能。 This class serves as the starting point of a kinematic chain and is responsible for computing forward kinematics, inverse kinematics, center of mass calculation, and inertia computation.
Scalar | 角度和位置的存储类型。 The storage type for angles and positions. |
Definition at line 552 of file kinematic.hpp.
|
inline |
构造 StartPoint
物体对象。 Constructs a StartPoint
object.
inertia | 物体的惯性参数。 The inertia parameters of the object. |
Definition at line 563 of file kinematic.hpp.
|
inline |
计算机器人系统的质心。 Computes the center of mass (CoM) of the robotic system.
该函数遍历所有关节,并利用惯性计算系统整体质心位置。 This function traverses all joints and uses inertia calculations to determine the overall center of mass.
Definition at line 620 of file kinematic.hpp.
|
inline |
计算当前状态的前向运动学(FK)。 Computes forward kinematics (FK) for the current state.
该函数遍历所有关节,根据当前状态计算其空间变换矩阵。 This function traverses all joints and calculates their spatial transformations based on the current state.
Definition at line 573 of file kinematic.hpp.
|
inline |
计算机器人系统的惯性分布。 Computes the inertia distribution of the robotic system.
该函数遍历所有关节,并根据质心和旋转惯性矩计算整体惯性分布。 This function traverses all joints and calculates the overall inertia distribution based on the center of mass and rotational inertia matrix.
Definition at line 604 of file kinematic.hpp.
|
inline |
计算目标状态的前向运动学(FK)。 Computes forward kinematics (FK) for the target state.
该函数用于目标位置调整,确保所有关节正确响应目标状态的变化。 This function is used for target position adjustments, ensuring all joints correctly respond to changes in the target state.
Definition at line 588 of file kinematic.hpp.
|
inlinestatic |
计算系统的质心。 Computes the center of mass of the system.
Definition at line 740 of file kinematic.hpp.
|
inlinestatic |
计算当前状态的前向运动学(FK)。 Computes forward kinematics (FK) for the current state.
Definition at line 680 of file kinematic.hpp.
|
inlinestatic |
计算机器人系统的惯性(后续遍历)。 Computes the inertia of the robotic system (subsequent traversal).
Definition at line 658 of file kinematic.hpp.
|
inlinestatic |
计算起始点惯性(首次遍历)。 Computes the inertia of the start point (first traversal).
Definition at line 630 of file kinematic.hpp.
|
inlinestatic |
计算目标状态的前向运动学(FK)。 Computes forward kinematics (FK) for the target state.
Definition at line 712 of file kinematic.hpp.
机器人质心。 The center of mass of the robot.
Definition at line 555 of file kinematic.hpp.