libxr 1.0
Want to be the best embedded framework
|
机器人中的物体(Object)类。 Object class representing an entity in the robot. More...
#include <kinematic.hpp>
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. | |
机器人中的物体(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.
Scalar | 角度和位置的存储类型。 The storage type for angles and positions. |
Definition at line 180 of file kinematic.hpp.
typedef List::Node<Joint<Scalar> *> LibXR::Kinematic::Object< Scalar >::Link |
关节链接类型。 Type for linking joints.
Definition at line 183 of file kinematic.hpp.
|
inline |
使用惯性参数构造 Object
对象。 Constructs an Object
using inertia parameters.
inertia | 物体的惯性参数。 The inertia parameters of the object. |
Definition at line 219 of file kinematic.hpp.
|
inlinevirtual |
Definition at line 247 of file kinematic.hpp.
设置物体的位置信息。 Sets the position of the object.
该函数将 pos
赋值给 runtime_.state
,用于更新物体的当前位置。 This function assigns pos
to runtime_.state
, updating the current position of the object.
pos | 物体的新位置。 The new position of the object. |
Definition at line 232 of file kinematic.hpp.
|
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.
quat | 物体的新旋转四元数。 The new quaternion representing the object's rotation. |
Definition at line 245 of file kinematic.hpp.
List LibXR::Kinematic::Object< Scalar >::joints |
物体的关节列表。 List of joints associated with the object.
Definition at line 206 of file kinematic.hpp.
Param LibXR::Kinematic::Object< Scalar >::param_ |
物体参数。 Object parameters.
Definition at line 210 of file kinematic.hpp.
指向父关节的指针。 Pointer to the parent joint.
Definition at line 208 of file kinematic.hpp.
Runtime LibXR::Kinematic::Object< Scalar >::runtime_ |
物体运行时状态。 Object runtime data.
Definition at line 211 of file kinematic.hpp.