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

机器人中的物体(Object)类。 Object class representing an entity in the robot. More...

#include <kinematic.hpp>

Inheritance diagram for LibXR::Kinematic::Object< Scalar >:
Collaboration diagram for LibXR::Kinematic::Object< Scalar >:

Data Structures

struct  Param
 物体参数结构体,存储物体的惯性参数。 Structure storing inertia parameters of the object. More...
 
struct  Runtime
 物体运行时状态结构体,存储物体的变换信息。 Structure storing runtime transformation data of the object. More...
 

Public Types

typedef List::Node< Joint< Scalar > * > Link
 关节链接类型。 Type for linking joints.
 

Public Member Functions

 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 ()
 

Data Fields

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.
 

Detailed Description

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

机器人中的物体(Object)类。 Object class representing an entity in the robot.

该类表示机器人中的刚性体,如连杆、基座等,并提供运动学计算方法。 This class represents rigid bodies in the robot, such as links and bases, and provides kinematic computation methods.

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

Definition at line 180 of file kinematic.hpp.

Member Typedef Documentation

◆ Link

关节链接类型。 Type for linking joints.

Definition at line 183 of file kinematic.hpp.

Constructor & Destructor Documentation

◆ Object()

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

使用惯性参数构造 Object 对象。 Constructs an Object using inertia parameters.

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

Definition at line 219 of file kinematic.hpp.

219: param_({inertia}) {}
Param param_
物体参数。 Object parameters.

Member Function Documentation

◆ CalcBackward()

template<typename Scalar >
virtual void LibXR::Kinematic::Object< Scalar >::CalcBackward ( )
inlinevirtual

Definition at line 247 of file kinematic.hpp.

247{}

◆ SetPosition()

template<typename Scalar >
void LibXR::Kinematic::Object< Scalar >::SetPosition ( const Position< Scalar > &  pos)
inline

设置物体的位置信息。 Sets the position of the object.

该函数将 pos 赋值给 runtime_.state,用于更新物体的当前位置。 This function assigns pos to runtime_.state, updating the current position of the object.

Parameters
pos物体的新位置。 The new position of the object.

Definition at line 232 of file kinematic.hpp.

232{ runtime_.state = pos; }
Runtime runtime_
物体运行时状态。 Object runtime data.
constexpr auto min(T1 a, T2 b) -> typename std::common_type< T1, T2 >::type
计算两个数的最小值
Transform< Scalar > state
物体的当前状态变换矩阵。 Transformation matrix of the current state.

◆ SetQuaternion()

template<typename Scalar >
void LibXR::Kinematic::Object< Scalar >::SetQuaternion ( const Quaternion< Scalar > &  quat)
inline

设置物体的旋转信息(四元数表示)。 Sets the rotation of the object using a quaternion.

该函数将 quat 赋值给 runtime_.state,用于更新物体的当前旋转状态。 This function assigns quat to runtime_.state, updating the current rotation state of the object.

Parameters
quat物体的新旋转四元数。 The new quaternion representing the object's rotation.

Definition at line 245 of file kinematic.hpp.

245{ runtime_.state = quat; }

Field Documentation

◆ joints

物体的关节列表。 List of joints associated with the object.

Definition at line 206 of file kinematic.hpp.

◆ param_

物体参数。 Object parameters.

Definition at line 210 of file kinematic.hpp.

◆ parent

指向父关节的指针。 Pointer to the parent joint.

Definition at line 208 of file kinematic.hpp.

◆ runtime_

物体运行时状态。 Object runtime data.

Definition at line 211 of file kinematic.hpp.


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