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

关节(Joint)类,表示机器人连杆间的旋转关节。 Joint class representing a rotational joint between robot links. More...

Collaboration diagram for LibXR::Kinematic::Joint< Scalar >:

Data Structures

struct  Param
 关节参数结构体。 Structure containing joint parameters. More...
 
struct  Runtime
 关节运行时状态结构体。 Structure containing runtime state of the joint. More...
 

Public Types

typedef struct LibXR::Kinematic::Joint::Param Param
 关节参数结构体。 Structure containing joint parameters.
 
typedef struct LibXR::Kinematic::Joint::Runtime Runtime
 关节运行时状态结构体。 Structure containing runtime state of the joint.
 

Public Member Functions

 Joint (Axis< Scalar > axis, Object< Scalar > *parent, Transform< Scalar > &parent2this, Object< Scalar > *child, Transform< Scalar > &this2child)
 构造 Joint 关节对象。 Constructs a Joint object.
 
void SetState (Scalar state)
 设置关节当前状态角度。 Sets the current state angle of the joint.
 
void SetTarget (Scalar target)
 设置关节的目标角度。 Sets the target angle of the joint.
 
void SetBackwardMult (Scalar mult)
 设置逆向运动学计算的步长系数。 Sets the step size coefficient for inverse kinematics calculations.
 

Data Fields

Runtime runtime_
 关节的运行时数据。 Runtime data of the joint.
 
Object< Scalar > * parent = nullptr
 指向父物体的指针。 Pointer to the parent object.
 
Object< Scalar > * child = nullptr
 指向子物体的指针。 Pointer to the child object.
 
Param param_
 关节的参数配置。 Parameters of the joint.
 

Detailed Description

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

关节(Joint)类,表示机器人连杆间的旋转关节。 Joint class representing a rotational joint between robot links.

该类包含关节的运动学信息,如旋转轴、前向/逆向运动学参数,并提供状态与目标设定方法。 This class contains kinematic information of the joint, such as rotation axis, forward/inverse kinematics parameters, and provides methods to set states and targets.

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

Definition at line 40 of file kinematic.hpp.

Constructor & Destructor Documentation

◆ Joint()

template<typename Scalar >
LibXR::Kinematic::Joint< Scalar >::Joint ( Axis< Scalar axis,
Object< Scalar > *  parent,
Transform< Scalar > &  parent2this,
Object< Scalar > *  child,
Transform< Scalar > &  this2child 
)
inline

构造 Joint 关节对象。 Constructs a Joint object.

Parameters
axis关节旋转轴。 Rotation axis of the joint.
parent关节的父对象。 Parent object of the joint.
parent2this父坐标系到该关节的变换。 Transform from the parent frame to this joint.
child关节的子对象。 Child object of the joint.
this2child该关节到子坐标系的变换。 Transform from this joint to the child frame.

Definition at line 99 of file kinematic.hpp.

101 : parent(parent), child(child), param_({parent2this, this2child, axis, 1.0})
102 {
103 runtime_.inertia = Eigen::Matrix<Scalar, 3, 3>::Zero();
104 auto link = new typename Object<Scalar>::Link(this);
105 parent->joints.Add(*link);
106 child->parent = this;
107 }
Object< Scalar > * parent
指向父物体的指针。 Pointer to the parent object.
Definition kinematic.hpp:83
Object< Scalar > * child
指向子物体的指针。 Pointer to the child object.
Definition kinematic.hpp:84
Param param_
关节的参数配置。 Parameters of the joint.
Definition kinematic.hpp:85
Runtime runtime_
关节的运行时数据。 Runtime data of the joint.
Definition kinematic.hpp:81
List::Node< Joint< Scalar > * > Link
关节链接类型。 Type for linking joints.
constexpr auto min(T1 a, T2 b) -> typename std::common_type< T1, T2 >::type
计算两个数的最小值
Eigen::Matrix< Scalar, 3, 3 > inertia
关节的惯性矩阵。 Inertia matrix of the joint.
Definition kinematic.hpp:70

Member Function Documentation

◆ SetBackwardMult()

template<typename Scalar >
void LibXR::Kinematic::Joint< Scalar >::SetBackwardMult ( Scalar  mult)
inline

设置逆向运动学计算的步长系数。 Sets the step size coefficient for inverse kinematics calculations.

该参数用于调整关节在逆向运动学计算中的变化速率。 This parameter adjusts the rate of change of the joint during inverse kinematics calculations.

Parameters
mult逆向运动学步长系数。 The step size coefficient.

Definition at line 165 of file kinematic.hpp.

165{ param_.ik_mult = mult; }
Scalar ik_mult
逆向运动学步长系数。 Step size coefficient for inverse kinematics.
Definition kinematic.hpp:55

◆ SetState()

template<typename Scalar >
void LibXR::Kinematic::Joint< Scalar >::SetState ( Scalar  state)
inline

设置关节当前状态角度。 Sets the current state angle of the joint.

该函数确保角度值在 [-π, π] 之间。 This function ensures the angle value remains within [-π, π].

Parameters
state需要设置的角度值(弧度)。 The angle value to be set (in radians).

Definition at line 118 of file kinematic.hpp.

119 {
120 if (state > M_PI)
121 {
122 state -= 2 * M_PI;
123 }
124 if (state < -M_PI)
125 {
126 state += 2 * M_PI;
127 }
128 runtime_.state_angle.angle() = state;
130 }
Axis< Scalar > axis
关节旋转轴。 Rotation axis of the joint.
Definition kinematic.hpp:53
Eigen::AngleAxis< Scalar > state_angle
当前关节角度状态。 Current joint angle state.
Definition kinematic.hpp:65

◆ SetTarget()

template<typename Scalar >
void LibXR::Kinematic::Joint< Scalar >::SetTarget ( Scalar  target)
inline

设置关节的目标角度。 Sets the target angle of the joint.

该函数确保目标角度值在 [-π, π] 之间。 This function ensures the target angle value remains within [-π, π].

Parameters
target目标角度值(弧度)。 The target angle value (in radians).

Definition at line 141 of file kinematic.hpp.

142 {
143 if (target > M_PI)
144 {
145 target -= 2 * M_PI;
146 }
147 if (target < -M_PI)
148 {
149 target += 2 * M_PI;
150 }
151 runtime_.target_angle.angle() = target;
153 }
Eigen::AngleAxis< Scalar > target_angle
目标关节角度状态。 Target joint angle state.
Definition kinematic.hpp:67

Field Documentation

◆ child

指向子物体的指针。 Pointer to the child object.

Definition at line 84 of file kinematic.hpp.

◆ param_

关节的参数配置。 Parameters of the joint.

Definition at line 85 of file kinematic.hpp.

◆ parent

指向父物体的指针。 Pointer to the parent object.

Definition at line 83 of file kinematic.hpp.

◆ runtime_

关节的运行时数据。 Runtime data of the joint.

Definition at line 81 of file kinematic.hpp.


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