🌡️ 传感器(Sensor)#

通过配置传感器,用户可以更方便的获取物理对象状态信息,如位置,旋转,速度,加速度等。传感器不会影响到物理仿真的结果,可以添加在不同的对象上,如刚体(Body),参考点(Site)等。传感器的配置示例可参考 examples/assets/site_and_sensor.xml

现在已经支持的传感器如下:#

类型

作用

返回值

加速度计(accelerometer)

三轴加速度计,用于测量安装点的线性加速度

list[float]
长度:3

速度计(velocimeter)

三轴速率计, 用于测量安装点的线性速度

list[float]
长度:3

角速度计(gryo)

用于测量安装点的角速度

list[float]
长度:3

扭矩计(torque)

用于测量安装点的扭矩大小

list[float]
长度:3

关节位置(jointpos)

用于测量关节的位置或角度

list[float]
长度:1

关节速度(jointvel)

用于测量关节的线速度或角速度

list[float]
长度:1

参考框位置(framepos)

参考框在全局坐标系下或指定参考坐标系下的位置

list[float]
长度:3

参考框旋转(framequat)

参考框在全局坐标系下的旋转四元数

list[float]
长度:4

参考框 X 轴(framexaxis)

参考框 X 轴在全局坐标系中的单位向量

list[float]
长度:3

参考框 Y 轴(frameyaxis)

参考框 Y 轴在全局坐标系中的单位向量

list[float]
长度:3

参考框 Z 轴(framezaxis)

参考框 Z 轴在全局坐标系中的单位向量

list[float]
长度:3

参考框线速度(framelinvel)

参考框在全局坐标系下的线速度

list[float]
长度:3

参考框角速度(frameangvel)

参考框在全局坐标系下的角速度

list[float]
长度:3

参考框线加速度(framelinacc)

参考框在全局坐标系下的线加速度

list[float]
长度:3

参考框角加速度(frameangacc)

参考框在全局坐标系下的角加速度

list[float]
长度:3

子树质心(subtreecom)

返回以指定刚体为根节点的运动学子树的质心(以全局坐标系表示)

list[float]
长度:3

子树线速度(subtreelinvel)

返回以指定刚体为根节点的运动学子树的质心的线速度(以全局坐标系表示)

list[float]
长度:3

子树角动量(subtreeangmom)

返回以指定刚体为根节点的运动学子树质心处的角动量(以全局坐标系表示)

list[float]
长度:3

相关 API 使用示例:#

获取某个指定的"sensor_name"的传感器数据

# Get sensor value directly
v0 = model.get_sensor_value("vel_0", data)
v1 = model.get_sensor_value("vel_1", data)
v2 = model.get_sensor_value("vel_2", data)
v3 = model.get_sensor_value("vel_3", data)
print(f"velocimeter values are : {v0}, {v1}, {v2}, {v3}")

acc_0 = model.get_sensor_value("acc_0", data)
acc_1 = model.get_sensor_value("acc_1", data)
acc_2 = model.get_sensor_value("acc_2", data)
acc_3 = model.get_sensor_value("acc_3", data)
print(f"accelerometer values are : {acc_0}, {acc_1}, {acc_2}, {acc_3}")

gyro_0 = model.get_sensor_value("gyro_0", data)
gyro_1 = model.get_sensor_value("gyro_1", data)
gyro_2 = model.get_sensor_value("gyro_2", data)
gyro_3 = model.get_sensor_value("gyro_3", data)
print(f"gyro values are : {gyro_0}, {gyro_1}, {gyro_2}, {gyro_3}")

获取模型中所有的传感器数据

sensor_values = model.get_sensor_values(data)
print(f"all sensor values are : {sensor_values}")

完整实例代码参见 examples/site_and_sensor.py