Orbit 使用指南 10|在机器人上安装传感器 | Isaac Sim | Omniverse

如是我闻: 资产类(asset classes)允许我们创建和模拟机器人,而传感器 (sensors) 则帮助我们获取关于环境的信息,获取不同的本体感知和外界感知信息。例如,摄像头传感器可用于获取环境的视觉信息,接触传感器可以用来获取机器人与环境的接触信息。

在本指南中,我们将看到如何给机器人添加不同的传感器。我们将在本指南中使用ANYmal-C机器人。ANYmal-C是一款四足机器人,拥有12个自由度,它有4条腿,每条腿有3个自由度。这款机器人配备了以下传感器:

  • 机器人头部的摄像头传感器,提供RGB-D图像
  • 提供地形高度信息的高度扫描传感器
  • 机器人脚部的接触传感器,提供接触信息

本指南对应于orbit/source/standalone/tutorials/04_sensors目录下的add_sensors_on_robot.py脚本。让我们先搂一眼完整的代码

# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""
This script demonstrates how to add and simulate on-board sensors for a robot.

We add the following sensors on the quadruped robot, ANYmal-C (ANYbotics):

* USD-Camera: This is a camera sensor that is attached to the robot's base.
* Height Scanner: This is a height scanner sensor that is attached to the robot's base.
* Contact Sensor: This is a contact sensor that is attached to the robot's feet.

.. code-block:: bash

    # Usage
    ./orbit.sh -p source/standalone/tutorials/04_sensors/add_sensors_on_robot.py

"""

from __future__ import annotations

"""Launch Isaac Sim Simulator first."""


import argparse

from omni.isaac.orbit.app import AppLauncher

# add argparse arguments
parser = argparse.ArgumentParser(description="Tutorial on adding sensors on a robot.")
parser.add_argument("--num_envs", type=int, default=2, help="Number of environments to spawn.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()

# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app

"""Rest everything follows."""

import torch
import traceback

import carb

import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.scene import InteractiveScene, InteractiveSceneCfg
from omni.isaac.orbit.sensors import CameraCfg, ContactSensorCfg, RayCasterCfg, patterns
from omni.isaac.orbit.utils import configclass

##
# Pre-defined configs
##
from omni.isaac.orbit_assets.anymal import ANYMAL_C_CFG  # isort: skip


@configclass
class SensorsSceneCfg(InteractiveSceneCfg):
    """Design the scene with sensors on the robot."""

    # ground plane
    ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())

    # lights
    dome_light = AssetBaseCfg(
        prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
    )

    # robot
    robot: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")

    # sensors
    camera = CameraCfg(
        prim_path="{ENV_REGEX_NS}/Robot/base/front_cam",
        update_period=0.1,
        height=480,
        width=640,
        data_types=["rgb", "distance_to_image_plane"],
        spawn=sim_utils.PinholeCameraCfg(
            focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
        ),
        offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
    )
    height_scanner = RayCasterCfg(
        prim_path="{ENV_REGEX_NS}/Robot/base",
        update_period=0.02,
        offset=RayCasterCfg.OffsetCfg(pos=(0.0, 0.0, 20.0)),
        attach_yaw_only=True,
        pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=[1.6, 1.0]),
        debug_vis=True,
        mesh_prim_paths=["/World/defaultGroundPlane"],
    )
    contact_forces = ContactSensorCfg(
        prim_path="{ENV_REGEX_NS}/Robot/.*_FOOT", update_period=0.0, history_length=6, debug_vis=True
    )


def run_simulator(
    sim: sim_utils.SimulationContext,
    scene: InteractiveScene,
):
    """Run the simulator."""

    # Define simulation stepping
    sim_dt = sim.get_physics_dt()
    sim_time = 0.0
    count = 0

    # Simulate physics
    while simulation_app.is_running():
        # Reset
        if count % 500 == 0:
            # reset counter
            count = 0
            # reset the scene entities
            # root state
            # we offset the root state by the origin since the states are written in simulation world frame
            # if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
            root_state = scene["robot"].data.default_root_state.clone()
            root_state[:, :3] += scene.env_origins
            scene["robot"].write_root_state_to_sim(root_state)
            # set joint positions with some noise
            joint_pos, joint_vel = (
                scene["robot"].data.default_joint_pos.clone(),
                scene["robot"].data.default_joint_vel.clone(),
            )
            joint_pos += torch.rand_like(joint_pos) * 0.1
            scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
            # clear internal buffers
            scene.reset()
            print("[INFO]: Resetting robot state...")
        # Apply default actions to the robot
        # -- generate actions/commands
        targets = scene["robot"].data.default_joint_pos
        # -- apply action to the robot
        scene["robot"].set_joint_position_target(targets)
        # -- write data to sim
        scene.write_data_to_sim()
        # perform step
        sim.step()
        # update sim-time
        sim_time += sim_dt
        count += 1
        # update buffers
        scene.update(sim_dt)

        # print information from the sensors
        print("-------------------------------")
        print(scene["camera"])
        print("Received shape of rgb   image: ", scene["camera"].data.output["rgb"].shape)
        print("Received shape of depth image: ", scene["camera"].data.output["distance_to_image_plane"].shape)
        print("-------------------------------")
        print(scene["height_scanner"])
        print("Received max height value: ", torch.max(scene["height_scanner"].data.ray_hits_w[..., -1]).item())
        print("-------------------------------")
        print(scene["contact_forces"])
        print("Received max contact force of: ", torch.max(scene["contact_forces"].data.net_forces_w).item())


def main():
    """Main function."""

    # Initialize the simulation context
    sim_cfg = sim_utils.SimulationCfg(dt=0.005, substeps=1)
    sim = sim_utils.SimulationContext(sim_cfg)
    # Set main camera
    sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
    # design scene
    scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
    scene = InteractiveScene(scene_cfg)
    # Play the simulator
    sim.reset()
    # Now we are ready!
    print("[INFO]: Setup complete...")
    # Run the simulator
    run_simulator(sim, scene)


if __name__ == "__main__":
    try:
        # run the main execution
        main()
    except Exception as err:
        carb.log_error(err)
        carb.log_error(traceback.format_exc())
        raise
    finally:
        # close sim app
        simulation_app.close()

代码解析

与之前我们在场景中添加资产的教程类似,传感器也是通过场景配置添加到场景中的。所有的传感器都继承自sensors.SensorBase类,并通过各自的配置类进行配置。每个传感器实例都可以定义自己的更新周期,即传感器更新的频率。更新周期通过sensors.SensorBaseCfg.update_period属性以秒为单位指定。

根据指定的路径和传感器类型,传感器会被附加到场景中的原始图元(prims)上。传感器可能直接和在场景中已创建的原始图元关联,或者可能被附加到一个已存在的原始图元上。例如,摄像头传感器会附加在一个已经创建好的原始图元上,而对于接触传感器,激活中的接触报告是刚体原始图元上的一个属性。

接下来,我们将介绍如何使用不同的传感器以及如何配置。要了解更多关于它们的描述,请查看sensors模块。

摄像头传感器 (Camera sensor)

摄像头是使用sensors.CameraCfg类来定义的。它基于USD摄像头传感器,不同的数据类型由Omniverse Replicator API来捕获。由于摄像头在场景中有对应的原始图元(prim),所以在指定的原始图元路径上会创建原始图元。

摄像头传感器的配置包括以下参数:

  • spawn:创建的USD摄像头类型。可以是PinholeCameraCfg(针孔摄像头配置)或FisheyeCameraCfg(鱼眼摄像头配置)。

  • offset:摄像头传感器相对于父原始图元的偏移。

  • data_types:要捕获的数据类型。可以是rgb、distance_to_image_plane(到图像平面的距离)、normals(法线)或其他USD摄像头传感器支持的类型。

为了将RGB-D摄像头传感器附加到机器人的头部,我们指定了一个相对于机器人基座的偏移(offset)。偏移是相对于基座指定的平移和旋转,以及偏移的指定方式。

接下来,我们来看如何使用摄像头传感器配置。我们将更新周期设置为0.1秒,这意味着摄像头传感器以10Hz的频率更新。原始图元路径表达式设置为{ENV_REGEX_NS}/Robot/base/front_cam,其中{ENV_REGEX_NS}是环境命名空间,"Robot"是机器人的名称,"base"是摄像头附加的原始图元的名称,而"front_cam"是与摄像头传感器关联的原始图元的名称。

高度扫描仪(scanner)

高度扫描仪作为一种虚拟传感器,通过使用NVIDIA Warp的光线投射内核来实现。通过sensors.RayCasterCfg,我们可以指定要投射的光线模式以及要对哪些网格进行光线投射。由于它们是虚拟传感器,在场景中没有相应的原始物体(prims)被创建。相反,它们附加到场景中的一个原始物体上,这用于指定传感器的位置。

在本指南中,基于光线投射的高度扫描仪附加到机器人的基座上。光线的模式使用pattern属性指定。对于均匀网格模式,我们使用GridPatternCfg指定模式。由于我们只关心高度信息,我们不需要考虑机器人的滚转和俯仰。因此,我们将attach_yaw_only设置为true。

对于高度扫描仪,我们可以可视化光线击中网格的点。这是通过将debug_vis属性设置为true来完成的。

高度扫描仪的整个配置如下:

   height_scanner = RayCasterCfg(
        prim_path="{ENV_REGEX_NS}/Robot/base",
        update_period=0.02,
        offset=RayCasterCfg.OffsetCfg(pos=(0.0, 0.0, 20.0)),
        attach_yaw_only=True,
        pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=[1.6, 1.0]),
        debug_vis=True,
        mesh_prim_paths=["/World/defaultGroundPlane"],
    )

接触传感器 (Contact sensor)

接触传感器利用PhysX的接触报告API来获取机器人与环境的接触信息。由于它依赖于PhysX,接触传感器期望在机器人的刚体上启用接触报告API。这可以通过在资产配置中设置activate_contact_sensors为true来完成。

通过sensors.ContactSensorCfg,可以指定我们想要获取接触信息的原始物体(prims)。可以设置额外的标志以获取更多关于接触的信息,例如接触空中时间、过滤原始物体之间的接触力等。

在本指南中,我们将接触传感器附加到机器人的脚上。机器人的脚被命名为"LF_FOOT"、“RF_FOOT”、“LH_FOOT"和"RF_FOOT”。我们传递一个正则表达式".*_FOOT"来简化原始物体路径的指定。这个正则表达式匹配所有以"_FOOT"结尾的原始物体。

我们将更新周期设置为0,以使传感器与模拟以相同的频率更新。此外,对于接触传感器,我们可以指定要存储的接触信息的历史长度。对于这个教程,我们将历史长度设置为6,这意味着存储了最后6个模拟步骤的接触信息。

接触传感器的整个配置如下:

    contact_forces = ContactSensorCfg(
        prim_path="{ENV_REGEX_NS}/Robot/.*_FOOT", update_period=0.0, history_length=6, debug_vis=True
    )

运行模拟循环

与使用资产时相似,传感器的缓冲区和物理句柄只有在播放模拟时才会初始化,即,在创建场景后调用sim.reset()是很重要的。

    # Play the simulator
    sim.reset()

除此之外,模拟循环与之前的指南类似。传感器作为场景更新的一部分进行更新,它们内部处理基于它们更新周期的缓冲区更新。

可以通过它们的data属性访问传感器的数据。作为示例,我们展示如何访问本教程中创建的不同传感器的数据:

        # print information from the sensors
        print("-------------------------------")
        print(scene["camera"])
        print("Received shape of rgb   image: ", scene["camera"].data.output["rgb"].shape)
        print("Received shape of depth image: ", scene["camera"].data.output["distance_to_image_plane"].shape)
        print("-------------------------------")
        print(scene["height_scanner"])
        print("Received max height value: ", torch.max(scene["height_scanner"].data.ray_hits_w[..., -1]).item())
        print("-------------------------------")
        print(scene["contact_forces"])
        print("Received max contact force of: ", torch.max(scene["contact_forces"].data.net_forces_w).item())

代码运行

现在让我们运行脚本并查看结果:

./orbit.sh -p source/standalone/tutorials/04_sensors/add_sensors_on_robot.py --num_envs 2

在这里插入图片描述

这个命令应该会打开一个带有地面平面、灯光和两个四足机器人的舞台。在机器人周围,应该会看到红色的球体,这些球体表示光线击中网格的点。另外,你可以切换视口到摄像机视图,以查看摄像头传感器捕获的RGB图像。请查看这里以了解如何切换视口到摄像机视图的更多信息。

要停止模拟,可以关闭窗口,或在终端中按Ctrl+C。

虽然在这个教程中,我们讲解了创建和使用不同的传感器,但在sensors模块中还有许多其他传感器可用。我们在source/standalone/tutorials/04_sensors目录中包含了使用这些传感器的示例。这些脚本可以使用以下命令运行:

# Frame Transformer
./orbit.sh -p source/standalone/tutorials/04_sensors/run_frame_transformer.py

# Ray Caster
./orbit.sh -p source/standalone/tutorials/04_sensors/run_ray_caster.py

# Ray Caster Camera
./orbit.sh -p source/standalone/tutorials/04_sensors/run_ray_caster_camera.py

# USD Camera
./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py

愿本文除一切机器人模拟器苦

以上

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.mfbz.cn/a/483145.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

5.windows Ubuntu 子系统,测序数据质量检测。

我们在得到一组或几组测序数据后,比如从测序公司拿到的测序数据为fastq.gz格式,首先我们需要对它们进行MD5检验,确保数据没有问题后才可进入以后的程序。(MD5可以进行测序数据完整性验证:MD5可以用于验证数据在传输或存…

IPMI开源库pyghmi基本使用

简介:Pyghmi是一个纯Python(主要是IPMI)服务器管理库。IPMI(Intelligent Platform Management Interface,智能平台管理接口)是一种开放的标准,旨在帮助系统管理员在本地和远程管理服务器系统。而…

第十届蓝桥杯大赛个人赛省赛(软件类)真题- CC++ 研究生组-最短路

6 肉眼观察&#xff0c; 看起来短的几条路对比下来是6~ #include <iostream> using namespace std; int main() {printf("6");return 0; }

AcWing 2060. 奶牛选美(每日一题)

目录 题目&#xff1a; 解题思路&#xff1a; 总结&#xff1a; 原题链接&#xff1a;2060. 奶牛选美 - AcWing题库 题目&#xff1a; 听说最近两斑点的奶牛最受欢迎&#xff0c;约翰立即购进了一批两斑点牛。 不幸的是&#xff0c;时尚潮流往往变化很快&#xff0c;当前…

[C语言]结构体、位段、枚举常量、联合体

目录 结构体 结构体的使用方法 结构体所占用的大小 位段 位段的使用方法 位段所占用的大小 枚举常量 枚举常量的使用方法 枚举常量的优势 联合体 联合体的使用方法 结构体 结构体的使用方法 结构体是一些值的集合&#xff0c;我们可以定义一个结构体&#xff0c;里…

实例:NX二次开发使用链表进行拉伸功能(链表相关功能练习)

一、概述 在进行批量操作时经常会利用链表进行存放相应特征的TAG值&#xff0c;以便后续操作&#xff0c;最常见的就是拉伸功能。这里我们以拉伸功能为例子进行说明。 二、常用链表相关函数 UF_MODL_create_list 创建一个链表&#xff0c;并返回链表的头指针。…

STM32---DHT11温湿度传感器与BH1750FVI光照传感器(HAL库、含源码)

写在前面&#xff1a;本节我们学习使用两个常见的传感器模块&#xff0c;分别为DHT11温湿度传感器以及BH1750FVI光照传感器,这两种传感器在对于环境监测中具有十分重要的作用&#xff0c;因为其使用简单方便&#xff0c;所以经常被用于STM32的项目之中。今天将使用分享给大家&a…

Digital WooCommerce Stores: 创建数字WordPress商店的详细教程- US Domain Center主机

第一步&#xff1a;了解数字 WooCommerce 商店 数字 WooCommerce 商店是一种电子商务模式&#xff0c;其中您可以销售虚拟产品&#xff0c;如在线课程、电子书、PDF、图像和视频。您可以使用 WooCommerce 插件在您的 WordPress 网站上设置数字产品&#xff0c;并通过在线交易提…

pandas的综合练习

事先说明&#xff1a; 由于每次都要导入库和处理中文乱码问题&#xff0c;我都是在最前面先写好&#xff0c;后面的代码就不在写了。要是copy到自己本地的话&#xff0c;就要把下面的代码也copy下。 # 准备工作import pandas as pd import numpy as np from matplotlib impor…

查立得php+mysql源码通用数据库配置教程

适用范围&#xff1a; 查分吧PHP多条件都输对版已有表万用查询系统 phpMySql已有数据表通用搜索可增删改查 查立得快搜系统(phpMysql) v20220208 查立得万能查&#xff08;phpmysql&#xff09; v20220512 及 各付费版 等几十款源码 数据库配置路径 数…

ReNamer Pro+Alist+RaiDrive妙用:实现批量修改网盘文件名称

ReNamer ProAlistRaiDrive妙用&#xff1a;批量修改管理网盘文件 说明工具下载Alist和RaiDrive安装和使用Renamer Pro激活和使用 说明 批量修改网盘文件名称的软件也大量存在&#xff0c;但是要么收费要么不好用&#xff0c;alist中也存在使用lamda表达式修改文件名称&#xf…

GT20L16S1Y标准汉字字库芯片完全解析(2)

接前一篇文章&#xff1a;GT20L16S1Y标准汉字字库芯片完全解析&#xff08;1&#xff09; 本文内容参考&#xff1a; 字库芯片GT20L16S1Y使用记录-CSDN博客 GT20L16S1Y字库IC驱动_gt20l16s1y字库芯片测试程序-CSDN博客 《GT20L16S1Y 标准点阵汉字库芯片产品规格书 V4.0I_K 2…

Day45:WEB攻防-PHP应用SQL二次注入堆叠执行DNS带外功能点黑白盒条件

目录 PHP-MYSQL-二次注入-DEMO&74CMS DEMO-用户注册登录修改密码 CMS-74CMS个人中心简历功能 PHP-MYSQL-堆叠注入-DEMO&CTF强网 Demo 2019强网杯-随便注&#xff08;CTF题型&#xff09; PHP-MYSQL-带外注入-DEMO&DNSLOG(让服务器主动把数据交出去) 知识点&…

C#,图论与图算法,输出无向图“欧拉路径”的弗勒里(Fleury Algorithm)算法和源程序

1 欧拉路径 欧拉路径是图中每一条边只访问一次的路径。欧拉回路是在同一顶点上开始和结束的欧拉路径。 这里展示一种输出欧拉路径或回路的算法。 以下是Fleury用于打印欧拉轨迹或循环的算法(源)。 1、确保图形有0个或2个奇数顶点。2、如果有0个奇数顶点,则从任意位置开始。…

I2C系列(三):软件模拟I2C读写24C04

一.目标 PC 端的串口调试软件通过 RS-485 与单片机通信&#xff0c;控制单片机利用软件模拟 I2C 总线对 EEPROM&#xff08;24C04&#xff09; 进行任意读写。 二.RS-485简述 在工业控制领域&#xff0c;传输距离越长&#xff0c;要求抗干扰能力也越强。由于 RS-232 无法消除…

【复杂网络建模】——XGI库进阶学习:生成随机超图

目录 一、构建随机超图 二、绘制随机超图 三、其他功能 3.1 访问超图的最大阶 3.2 列出所有边尺寸 3.3 边大小的直方图 3.4 节点度直方图 一、构建随机超图 XGI&#xff08;eXtensible Graphs and Hypergraphs&#xff09;是一个Python库&#xff0c;专注于超图&#…

ARM CPU的总线发展

ARM架构是当今世界上最为广泛应用的嵌入式处理器架构之一&#xff0c;其CPU总线的发展对于系统性能和扩展性具有重要影响。本文将探讨ARM CPU总线的发展历程、关键技术和对系统性能的影响。 以下是我整理的关于嵌入式开发的一些入门级资料&#xff0c;免费分享给大家&#xff…

Flutter学习10 - Json解析与Model使用

对于网络请求返回的 Json 数据&#xff0c;一般会进行如下解析&#xff1a; 将 Json String 解析为 Map<String, dynamic>将 Json String 解析为 Dart Model 发起一个返回 Json String 的网络请求 import package:http/http.dart as http;void main() {_doGet(); }_do…

计算机网络——26通用转发和SDN

通用转发和SDN 网络层功能&#xff1a; 转发&#xff1a; 对于从某个端口 到来的分组转发到合适的 输出端口路由&#xff1a; 决定分组从源端 到目标端的路径 网络层 传统路由器的功能 每个路由器(Per Route)的控制平面 &#xff08;传统&#xff09; 每个路由器上都有实…

本地运行环境工具UPUPWANK(win)和Navicat数据库管理工具

UPUPWANK安装地址&#xff1a;https://www.upupw.net 1.进入UPUPWANK后点击一键开启 2.新增项目 这里请千万注意80端口&#xff0c;如果80端口被占用了&#xff0c;请记住去任务管理器关闭占用80端口的进程。不然就不会成功显示。&#xff08;笔者含泪警告&#xff0c;一晚上的…