Vision sensors分为正交投影型(Orthographic projection-type)和透视投影(Perspective projection-type),视场形状如下:

1)Enable all vision sensors:打开和关闭一切Vision Sensor功能
2)Explicit handling:指示传感器是否应显式处理。如果选择此选项,则仅作为调用sim.handleVisionSensor(sim.handle_all)或sim.handleVisionSensor(visionSensorHandle)传感器只有在处理时才能处理。如果用户想在子脚本中处理传感器而不是在主脚本中,这将非常有用(如果没有选择,则在主脚本中调用sim.handleVisionSensor(sim.handle_all_except_explicit)传感器将被处理两次,并在子脚本中调用sim.handleVisionSensor(visionSensorHandle)时一次。另外,请参考显式和非显式调用部分
3)External input:选择外部输入后,将更改视觉传感器的正常运行,以处理外部图像(如视频图像)
4)Perspective mode:允许在透视投影类型和正交投影类型之间选择视觉传感器
5)Ignore RGB info (faster):如果选择该选项,传感器将被忽略RGB为了更快地运行,信息(即颜色)。如果仅依赖于传感器的深度信息,请使用此选项
6)Ignore depth info (faster):如果选择此选项,将忽略传感器的深度信息,以便更快地运行。如果您不想使用传感器的深度信息,请使用此选项
7)Packet1 is blank (faster):若选择,则CoppeliaSim具体信息不会自动从获得的图像中提取,因此可以更快地运行。如果您不打算使用它API函数sim.readVisionSensor或sim.handleVisionSensor请使用此选项返回的第一个辅助值数据包
8)Use local lights:如果使用,则只激活与视觉传感器相关的局部光源(即内置在视觉传感器上)。Lights可本地化照明属性。
9)Show fog if enabled:如果禁用,启用雾后视觉传感器将看不到雾
10)Render mode(渲染模式)
OpenGL (default):渲染对象的可见颜色通道,默认选项
OpenGL, auxiliary channels:渲染对象的辅助颜色通道。辅助通道为红色、绿色和蓝色:红色为温度通道(环境温度为0.5)绿色是用户定义的通道,蓝色是活动发光通道
OpenGL, color coded handles:渲染象的句柄编码成颜色来渲染对象。sim.readVisionSensor或sim.handleVisionSensor API函数返回的第一个数据包代表检测到的对象句柄(四舍五入值)
POV-Ray:使用POV-Ray插件渲染图像,使阴影(包括柔和阴影)和材材料效果(慢得多)
External renderer:通过插件实现的外部渲染器
External renderer, windowed:使用通过插件实现的外部渲染器,并在外显示图像(仅在模拟过程中)
OpenGL3:使用OpenGL渲染器插件,由Stephen James提供。提供了插件CoppeliaSim阴影投射在中间是无法实现的。通过对象的扩展字符串(例如openGL3 {lightProjection {nearPlane {0.1} farPlane {10} orthoSize {8} bias {0.001} normalBias {0.005} shadowTextureSize {2048}})针对每种光调整光投射和阴影
OpenGL3, windowed:和上面一样,但是有窗户
11)Near / far clipping plane:传感器将能够检测到最小/最大距离
12)Perspective angle:当传感器处于透视模式时,检测体积的最大开角
13)Orthographic size:当传感器不在透视模式下检测体积的最大尺寸时(沿x或y)
14)Resolution X / Y:视觉传感器捕获图像所需x/y分辨率
15)Adjust default image color:允许在未渲染任何内容的区域指定颜色。默认情况下,将使用环境雾颜色。
在场景中添加一个Perspective type在环境中点设置相关属性参数的视觉传感器类型add/Floating view,右击窗口,点击view,增加相关性的视觉传感器,此时仿真可以看到视觉传感器的图像。
- 获取传感器句柄。errorCode, visionSensorHandle = vrep.simxGetObjectHandle (clientID, 'Vision_sensor', vrep.simx_opmode_oneshot_wait)
- 获取视觉传感器的数据。errprCode, resolution, image = vrep.simxGetVisionSensorImage (clientID, visionSensorHandle, 0,vrep.simx_opmode_buffer)
Resolution存储原图像的像素,image存储具体数据信息
- 图像格式转换
- 可以加循环,重复读取,便可以获得动态视频,循环在第二次调用vrep.simxGetVisionSensorImage时加,后面改为使用opencv对数据图像读取。mpl.show()带有阻塞,只能显示一张图片。
四、相关代码:
#!/usr/bin/env python
# encoding: utf-8
import vrep
import sys
import numpy as np
import math
import matplotlib.pyplot as mpl
import time
import cv2
class Usage(Exception):
def __init__(self, msg):
self.msg = msg
def main(argv=None):
if argv is None:
argv = sys.argv
# Python connect to the V-REP client
vrep.simxFinish(-1)
clientID = vrep.simxStart('127.0.0.1', 19997, True, True, 5000, 5)
if clientID != -1:
print("Connected to remote API server")
else:
print("Connection not successful")
sys.exit("Connected failed,program ended!")
# Get the handle of vision sensor
errorCode, visionSensorHandle = vrep.simxGetObjectHandle(clientID, 'Vision_sensor', vrep.simx_opmode_oneshot_wait)
# Get the image of vision sensor
errprCode, resolution, image = vrep.simxGetVisionSensorImage(clientID, visionSensorHandle, 0,
vrep.simx_opmode_streaming)
time.sleep(0.5)
while True:
errprCode, resolution, image = vrep.simxGetVisionSensorImage(clientID, visionSensorHandle, 0,
vrep.simx_opmode_buffer)
#print(image)
# Process the image to the format (64,64,3)
sensorImage = []
sensorImage = np.array(image, dtype=np.uint8)
sensorImage.resize([resolution[0], resolution[1], 3])
print(sensorImage.shape)
# Use matplotlib.imshow to show the image
sensorImage=cv2.flip(sensorImage, 0)
cv2.imshow('image',sensorImage)
cv2.waitKey(1)
#mpl.show()cv2.imshow('tracking', image)
if __name__ == "__main__":
sys.exit(main())