跳转至主要内容
Ctrl+K
Genesis 0.2.0 文档 - Home Genesis 0.2.0 文档 - Home
  • 用户指南
  • API 参考
  • 路线图
  • 用户指南
  • API 参考
  • 路线图

章节导航

  • Scene
    • 场景 (Scene)
    • 仿真器 (Simulator)
  • Entity
    • RigidEntity(刚体实体)
      • RigidEntity(刚体实体)
      • RigidLink(刚体连杆)
      • RigidJoint(刚体关节)
      • RigidGeom(刚体几何体)
      • RigidVisGeom(刚体可视化几何体)
    • MPMEntity(材料点法实体)
    • FEMEntity(有限元法实体)
    • PBDEntity(基于位置的动力学实体)
      • PBDParticleEntity(PBD 粒子实体)
      • PBDFreeParticleEntity(PBD 自由粒子实体)
      • PBD2DEntity(PBD 2D 实体)
      • PBD3DEntity(PBD 3D 实体)
      • PBDTetEntity(PBD 四面体实体)
    • SPHEntity(光滑粒子流体动力学实体)
    • DroneEntity(无人机实体)
    • HybridEntity(混合实体)
    • Emitter(发射器)
  • 可视化与渲染
    • Visualizer
    • Viewer
    • 渲染器(Renderers)
      • Rasterizer
      • Raytracer
      • BatchRenderer
    • 相机(Cameras)
      • Camera
    • 灯光(Lights)
  • Sensors
    • 相机 (Camera)
    • 接触传感器
    • IMU 传感器
    • 射线投射传感器
  • 记录与回放
    • Recorder
    • RecorderManager
    • File Writers
    • Plotters
  • 物理引擎
    • Solvers (求解器)
      • RigidSolver
      • MPMSolver
      • FEMSolver
      • PBDSolver
      • SPHSolver
      • SFSolver
      • ToolSolver
    • Couplers
      • LegacyCoupler
      • SAPCoupler
      • IPCCoupler
    • States
  • Material
    • gs.materials.Rigid
    • MPM(材料点法)
      • gs.materials.MPM.Elastic
      • gs.materials.MPM.ElastoPlastic
      • gs.materials.MPM.Liquid
      • gs.materials.MPM.Muscle
      • gs.materials.MPM.Sand
      • gs.materials.MPM.Snow
    • FEM(有限元法)
      • gs.materials.FEM.Elastic
      • gs.materials.FEM.Muscle
    • PBD(基于位置的动力学)
      • gs.materials.PBD.Elastic
      • gs.materials.PBD.Cloth
      • gs.materials.PBD.Liquid
      • gs.materials.PBD.Particle
    • SPH(光滑粒子流体动力学)
      • gs.materials.SPH.Liquid
    • gs.materials.Hybrid
  • Options
    • gs.options.Options
    • 仿真器、耦合器与求解器选项
      • gs.options.SimOptions
      • gs.options.CouplerOptions
      • gs.options.ToolOptions
      • gs.options.RigidOptions
      • gs.options.MPMOptions
      • gs.options.SPHOptions
      • gs.options.PBDOptions
      • gs.options.FEMOptions
      • gs.options.SFOptions
    • Morph
      • gs.morphs.Morph
      • 基本体
        • gs.morphs.Primitive
        • gs.morphs.Box
        • gs.morphs.Sphere
        • gs.morphs.Cylinder
        • gs.morphs.Plane
      • 文件变形
        • gs.morphs.FileMorph
        • gs.morphs.Mesh
        • gs.morphs.URDF
        • gs.morphs.MJCF
        • gs.morphs.Terrain
        • gs.morphs.Drone
    • 渲染器
      • gs.renderers.Renderer 渲染器配置基类
      • gs.renderers.Rasterizer 光栅化渲染器
      • gs.renderers.RayTracer 光线追踪渲染器
      • gs.renderers.BatchRenderer
    • 表面材质 (Surface)
      • gs.surfaces.Surface
      • 塑料
        • gs.surfaces.Plastic
        • gs.surfaces.Rough
        • gs.surfaces.Smooth
        • gs.surfaces.Reflective
        • gs.surfaces.Collision
        • gs.surfaces.Default
      • 金属
        • gs.surfaces.Metal
        • gs.surfaces.Iron
        • gs.surfaces.Aluminium
        • gs.surfaces.Copper
        • gs.surfaces.Gold
      • 自发光 (Emission)
        • gs.surfaces.Emission
      • 玻璃
        • gs.surfaces.Glass
        • gs.surfaces.Water
    • 纹理
      • gs.textures.Texture
      • gs.textures.ColorTexture
      • gs.textures.ImageTexture
    • 查看器与可视化
      • gs.options.ViewerOptions 选项
      • gs.options.VisOptions
  • 工具与辅助函数
    • Constants & Enums
    • Device & Platform Utilities
    • Tensor Utilities
    • Geometry Utilities
    • File I/O Utilities
  • 可微分仿真
    • Tensor
    • 创建操作
  • API 参考
  • Entity
  • RigidEntity(刚体实体)
  • RigidLink(刚体连杆)

RigidLink(刚体连杆)#

gs.RigidLink 是 Genesis 项目中的一个类,表示刚性链接。它继承自 RigidEntity 类,并包含以下成员:

class genesis.engine.entities.rigid_entity.rigid_link.RigidLink(entity, name, idx, geom_start, cell_start, vert_start, face_start, edge_start, vgeom_start, vvert_start, vface_start, pos, quat, inertial_pos, inertial_quat, inertial_i, inertial_mass, parent_idx, invweight, visualize_contact)[源代码]#

基类:RBC

RigidLink class. One RigidEntity consists of multiple RigidLinks, each of which is a rigid body and could consist of multiple RigidGeoms (link.geoms, for collision) and RigidVisGeoms (link.vgeoms for visualization).

get_pos(envs_idx=None)[源代码]#

Get the position of the link in the world frame.

参数:

envs_idx (int or array of int, optional) – The indices of the environments to get the position. If None, get the position of all environments. Default is None.

get_quat(envs_idx=None)[源代码]#

Get the quaternion of the link in the world frame.

参数:

envs_idx (int or array of int, optional) – The indices of the environments to get the quaternion. If None, get the quaternion of all environments. Default is None.

get_vel(envs_idx=None)[源代码]#

Get the linear velocity of the link in the world frame.

参数:

envs_idx (int or array of int, optional) – The indices of the environments to get the linear velocity. If None, get the linear velocity of all environments. Default is None.

get_ang(envs_idx=None)[源代码]#

Get the angular velocity of the link in the world frame.

参数:

envs_idx (int or array of int, optional) – The indices of the environments to get the angular velocity. If None, get the angular velocity of all environments. Default is None.

get_verts()[源代码]#

Get the vertices of the link’s collision body (concatenation of all link.geoms) in the world frame.

get_vverts()[源代码]#

Get the vertices of the link’s visualization body (concatenation of all link.vgeoms) in the world frame.

get_AABB()[源代码]#

Get the axis-aligned bounding box (AABB) of the link’s collision body (concatenation of all link.geoms) in the world frame.

get_vAABB()[源代码]#

Get the axis-aligned bounding box (AABB) of the link’s visual body (concatenation of all link.vgeoms) in the world frame.

set_mass(mass)[源代码]#

Set the mass of the link.

get_mass()[源代码]#

Get the mass of the link.

set_friction(friction)[源代码]#

Set the friction of all the link’s geoms.

property uid#

The unique ID of the link.

property name#

The name of the link.

property entity#

The entity that the link belongs to.

property solver#

The solver that the link belongs to.

property visualize_contact#

Whether to visualize the contact of the link.

property joint#

The joint that connects the link to its parent link.

property idx#

The global index of the link in the RigidSolver.

property parent_idx#

The global index of the link’s parent link in the RigidSolver. If the link is the root link, return -1.

property child_idxs#

The global indices of the link’s child links in the RigidSolver.

property idx_local#

The local index of the link in the entity.

property parent_idx_local#

The local index of the link’s parent link in the entity. If the link is the root link, return -1.

property child_idxs_local#

The local indices of the link’s child links in the entity.

property is_leaf#

Whether the link is a leaf link (i.e., has no child links).

property invweight#

The invweight of the link.

property pos#

The initial position of the link. For real-time position, use link.get_pos().

property quat#

The initial quaternion of the link. For real-time quaternion, use link.get_quat().

property inertial_pos#

The initial position of the link’s inertial frame.

property inertial_quat#

The initial quaternion of the link’s inertial frame.

property inertial_mass#

The initial mass of the link.

property inertial_i#

The inerial matrix of the link.

property geoms#

The list of the link’s collision geometries (RigidGeom).

property vgeoms#

The list of the link’s visualization geometries (RigidVisGeom).

property n_geoms#

Number of the link’s collision geometries.

property geom_start#

The start index of the link’s collision geometries in the RigidSolver.

property geom_end#

The end index of the link’s collision geometries in the RigidSolver.

property n_vgeoms#

Number of the link’s visualization geometries (vgeom).

property vgeom_start#

The start index of the link’s vgeom in the RigidSolver.

property vgeom_end#

The end index of the link’s vgeom in the RigidSolver.

property n_cells#

Number of sdf cells of all the link’s geoms.

property n_verts#

Number of vertices of all the link’s geoms.

property n_vverts#

Number of vertices of all the link’s vgeoms.

property n_faces#

Number of faces of all the link’s geoms.

property n_vfaces#

Number of faces of all the link’s vgeoms.

property n_edges#

Number of edges of all the link’s geoms.

property is_built#

Whether the entity the link belongs to is built.

上一页

RigidEntity(刚体实体)

下一页

RigidJoint(刚体关节)

当前页面
  • RigidLink
    • RigidLink.get_pos()
    • RigidLink.get_quat()
    • RigidLink.get_vel()
    • RigidLink.get_ang()
    • RigidLink.get_verts()
    • RigidLink.get_vverts()
    • RigidLink.get_AABB()
    • RigidLink.get_vAABB()
    • RigidLink.set_mass()
    • RigidLink.get_mass()
    • RigidLink.set_friction()
    • RigidLink.uid
    • RigidLink.name
    • RigidLink.entity
    • RigidLink.solver
    • RigidLink.visualize_contact
    • RigidLink.joint
    • RigidLink.idx
    • RigidLink.parent_idx
    • RigidLink.child_idxs
    • RigidLink.idx_local
    • RigidLink.parent_idx_local
    • RigidLink.child_idxs_local
    • RigidLink.is_leaf
    • RigidLink.invweight
    • RigidLink.pos
    • RigidLink.quat
    • RigidLink.inertial_pos
    • RigidLink.inertial_quat
    • RigidLink.inertial_mass
    • RigidLink.inertial_i
    • RigidLink.geoms
    • RigidLink.vgeoms
    • RigidLink.n_geoms
    • RigidLink.geom_start
    • RigidLink.geom_end
    • RigidLink.n_vgeoms
    • RigidLink.vgeom_start
    • RigidLink.vgeom_end
    • RigidLink.n_cells
    • RigidLink.n_verts
    • RigidLink.n_vverts
    • RigidLink.n_faces
    • RigidLink.n_vfaces
    • RigidLink.n_edges
    • RigidLink.is_built
由 GitHub 编辑

本页

  • 显示源代码

© Copyright 2024, Genesis Developers.

由 Sphinx 6.2.1创建。

使用 PyData Sphinx Theme 0.16.1构建.