libxr  1.0
Want to be the best embedded framework
Loading...
Searching...
No Matches
LibXR::Kinematic::StartPoint< Scalar > Class Template Reference

机器人起始点(StartPoint)类,继承自 Object。 StartPoint class representing the base or root of a robotic kinematic chain, inheriting from Object. More...

#include <kinematic.hpp>

Inheritance diagram for LibXR::Kinematic::StartPoint< Scalar >:
[legend]
Collaboration diagram for LibXR::Kinematic::StartPoint< Scalar >:
[legend]

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.
 
- Public Member Functions inherited from LibXR::Kinematic::Object< Scalar >
 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.
 
- Data Fields inherited from LibXR::Kinematic::Object< Scalar >
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

- Public Types inherited from LibXR::Kinematic::Object< Scalar >
typedef List::Node< Joint< Scalar > * > Link
 关节链接类型。 Type for linking joints.
 

Detailed Description

template<typename Scalar>
class LibXR::Kinematic::StartPoint< Scalar >

机器人起始点(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.

Template Parameters
Scalar角度和位置的存储类型。 The storage type for angles and positions.

Definition at line 560 of file kinematic.hpp.

Constructor & Destructor Documentation

◆ StartPoint()

template<typename Scalar >
LibXR::Kinematic::StartPoint< Scalar >::StartPoint ( Inertia< Scalar > & inertia)
inline

构造 StartPoint 物体对象。 Constructs a StartPoint object.

Parameters
inertia物体的惯性参数。 The inertia parameters of the object.

Definition at line 571 of file kinematic.hpp.

571: Object<Scalar>(inertia) {}
Object(Inertia< Scalar > &inertia)
使用惯性参数构造 Object 对象。 Constructs an Object using inertia parameters.

Member Function Documentation

◆ CalcCenterOfMass()

template<typename Scalar >
void LibXR::Kinematic::StartPoint< Scalar >::CalcCenterOfMass ( )
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 628 of file kinematic.hpp.

629 {
630 this->cog = CenterOfMass<Scalar>(this->param_.inertia, this->runtime_.state);
632 }
Param param_
物体参数。 Object parameters.
List joints
物体的关节列表。 List of joints associated with the object.
static ErrorCode CenterOfMassForeachFunLoop(Joint< Scalar > *joint, StartPoint< Scalar > &start)
计算系统的质心。 Computes the center of mass of the system.
CenterOfMass< Scalar > cog
机器人质心。 The center of mass of the robot.
ErrorCode Foreach(Func func)
遍历链表中的每个节点,并应用回调函数。 Iterates over each node in the list and applies a callback function.
Definition list.hpp:172

◆ CalcForward()

template<typename Scalar >
void LibXR::Kinematic::StartPoint< Scalar >::CalcForward ( )
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 581 of file kinematic.hpp.

582 {
583 this->runtime_.target = this->runtime_.state;
584 auto fun = [&](Joint<Scalar> *joint) { return ForwardForeachFunLoop(joint, *this); };
585 this->joints.template Foreach<Joint<Scalar> *>(fun);
586 }
Runtime runtime_
物体运行时状态。 Object runtime data.
static ErrorCode ForwardForeachFunLoop(Joint< Scalar > *joint, StartPoint< Scalar > &start)
计算当前状态的前向运动学(FK)。 Computes forward kinematics (FK) for the current state.
Transform< Scalar > target
物体的目标状态变换矩阵。 Transformation matrix of the target state.
Transform< Scalar > state
物体的当前状态变换矩阵。 Transformation matrix of the current state.

◆ CalcInertia()

template<typename Scalar >
void LibXR::Kinematic::StartPoint< Scalar >::CalcInertia ( )
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 612 of file kinematic.hpp.

613 {
614 Joint<Scalar> *res = nullptr;
615 auto fun = [&](Joint<Scalar> *joint)
616 { return InertiaForeachFunLoopStart(joint, res); };
617 this->joints.template Foreach<Joint<Scalar> *>(fun);
618 }
static ErrorCode InertiaForeachFunLoopStart(Joint< Scalar > *joint, Joint< Scalar > *parent)
计算起始点惯性(首次遍历)。 Computes the inertia of the start point (first traversal).

◆ CalcTargetForward()

template<typename Scalar >
void LibXR::Kinematic::StartPoint< Scalar >::CalcTargetForward ( )
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 596 of file kinematic.hpp.

597 {
598 this->runtime_.target = this->runtime_.state;
599 auto fun = [&](Joint<Scalar> *joint)
600 { return TargetForwardForeachFunLoop(joint, *this); };
601 this->joints.template Foreach<Joint<Scalar> *>(fun);
602 }
static ErrorCode TargetForwardForeachFunLoop(Joint< Scalar > *joint, StartPoint< Scalar > &start)
计算目标状态的前向运动学(FK)。 Computes forward kinematics (FK) for the target state.

◆ CenterOfMassForeachFunLoop()

template<typename Scalar >
static ErrorCode LibXR::Kinematic::StartPoint< Scalar >::CenterOfMassForeachFunLoop ( Joint< Scalar > * joint,
StartPoint< Scalar > & start )
inlinestatic

计算系统的质心。 Computes the center of mass of the system.

Definition at line 748 of file kinematic.hpp.

750 {
751 CenterOfMass<Scalar> child_cog(joint->child->param_.inertia,
752 joint->child->runtime_.state);
753
754 start.cog += child_cog;
755
756 joint->child->joints.Foreach(TargetForwardForeachFunLoop, start);
757
758 return ErrorCode::OK;
759 }

◆ ForwardForeachFunLoop()

template<typename Scalar >
static ErrorCode LibXR::Kinematic::StartPoint< Scalar >::ForwardForeachFunLoop ( Joint< Scalar > * joint,
StartPoint< Scalar > & start )
inlinestatic

计算当前状态的前向运动学(FK)。 Computes forward kinematics (FK) for the current state.

Definition at line 688 of file kinematic.hpp.

689 {
690 Transform<Scalar> t_joint(joint->parent->runtime_.state + joint->param_.parent2this);
691
692 joint->runtime_.state = t_joint;
693
694 Transform<Scalar> t_child(
695 joint->runtime_.state.rotation * joint->runtime_.state_angle,
696 joint->runtime_.state.translation);
697
698 t_child = t_child + joint->param_.this2child;
699
700 joint->child->runtime_.state = t_child;
701 joint->runtime_.state_axis = joint->runtime_.state.rotation * joint->param_.axis;
702 joint->runtime_.target_axis = joint->runtime_.state_axis;
703
704 joint->runtime_.target = joint->runtime_.state;
705 joint->runtime_.target_angle = joint->runtime_.state_angle;
706 joint->child->runtime_.target = joint->child->runtime_.state;
707
708 auto fun = [&](Joint<Scalar> *child_joint)
709 { return ForwardForeachFunLoop(child_joint, start); };
710
711 joint->child->joints.template Foreach<Joint<Scalar> *>(fun);
712
713 return ErrorCode::OK;
714 }

◆ InertiaForeachFunLoop()

template<typename Scalar >
static ErrorCode LibXR::Kinematic::StartPoint< Scalar >::InertiaForeachFunLoop ( Joint< Scalar > * joint,
Joint< Scalar > * parent )
inlinestatic

计算机器人系统的惯性(后续遍历)。 Computes the inertia of the robotic system (subsequent traversal).

Definition at line 666 of file kinematic.hpp.

667 {
668 auto new_inertia =
669 joint->child->param_.inertia
670 .Translate(parent->runtime_.state.translation -
671 joint->child->runtime_.state.translation)
672 .Rotate(parent->runtime_.state.rotation / joint->runtime_.state.rotation);
673
674 parent->runtime_.inertia = new_inertia + parent->runtime_.inertia;
675
676 auto fun_loop = [&](Joint<Scalar> *child_joint)
677 { return InertiaForeachFunLoop(child_joint, joint); };
678
679 joint->child->joints.template Foreach<Joint<Scalar> *>(fun_loop);
680
681 return ErrorCode::OK;
682 }
Joint< Scalar > * parent
指向父关节的指针。 Pointer to the parent joint.
static ErrorCode InertiaForeachFunLoop(Joint< Scalar > *joint, Joint< Scalar > *parent)
计算机器人系统的惯性(后续遍历)。 Computes the inertia of the robotic system (subsequent traversal).

◆ InertiaForeachFunLoopStart()

template<typename Scalar >
static ErrorCode LibXR::Kinematic::StartPoint< Scalar >::InertiaForeachFunLoopStart ( Joint< Scalar > * joint,
Joint< Scalar > * parent )
inlinestatic

计算起始点惯性(首次遍历)。 Computes the inertia of the start point (first traversal).

Definition at line 638 of file kinematic.hpp.

639 {
640 UNUSED(parent);
641 joint->runtime_.inertia = joint->child->param_.inertia
642 .Translate(joint->runtime_.state.translation -
643 joint->child->runtime_.state.translation)
644 .Rotate(joint->child->runtime_.state.rotation /
645 joint->runtime_.state.rotation);
646
647 joint->runtime_.inertia = Inertia<Scalar>::Rotate(
648 joint->runtime_.inertia, Eigen::Quaternion<Scalar>(joint->runtime_.state_angle));
649
650 auto fun_loop = [&](Joint<Scalar> *child_joint)
651 { return InertiaForeachFunLoop(child_joint, joint); };
652
653 auto fun_start = [&](Joint<Scalar> *child_joint)
654 { return InertiaForeachFunLoopStart(child_joint, joint); };
655
656 joint->child->joints.template Foreach<Joint<Scalar> *>(fun_loop);
657 joint->child->joints.template Foreach<Joint<Scalar> *>(fun_start);
658
659 return ErrorCode::OK;
660 }
Inertia Rotate(const Eigen::Matrix< Scalar, 3, 3 > &R) const
旋转惯性张量。Rotates the inertia tensor.
Definition inertia.hpp:170

◆ TargetForwardForeachFunLoop()

template<typename Scalar >
static ErrorCode LibXR::Kinematic::StartPoint< Scalar >::TargetForwardForeachFunLoop ( Joint< Scalar > * joint,
StartPoint< Scalar > & start )
inlinestatic

计算目标状态的前向运动学(FK)。 Computes forward kinematics (FK) for the target state.

Definition at line 720 of file kinematic.hpp.

722 {
723 Transform<Scalar> t_joint(joint->parent->runtime_.target + joint->param_.parent2this);
724
725 joint->runtime_.target = t_joint;
726
727 Transform<Scalar> t_child(
728 joint->runtime_.target.rotation * joint->runtime_.target_angle,
729 joint->runtime_.target.translation);
730
731 t_child = t_child + joint->param_.this2child;
732 joint->child->runtime_.target = t_child;
733
734 joint->runtime_.target_axis = joint->runtime_.target.rotation * joint->param_.axis;
735
736 auto fun = [&](Joint<Scalar> *child_joint)
737 { return TargetForwardForeachFunLoop(child_joint, start); };
738
739 joint->child->joints.template Foreach<Joint<Scalar> *>(fun);
740
741 return ErrorCode::OK;
742 }

Field Documentation

◆ cog

template<typename Scalar >
CenterOfMass<Scalar> LibXR::Kinematic::StartPoint< Scalar >::cog

机器人质心。 The center of mass of the robot.

Definition at line 563 of file kinematic.hpp.


The documentation for this class was generated from the following file: