PyBullet笔记(七)获取键盘事件和鼠标事件
上一章传送门:
除了设置控件手动传参,pybullet还允许用户自定义键盘事件和鼠标事件的处理逻辑。
比如pybullet默认的鼠标事件是可以将物体原地拔起,扔出去。默认的键盘事件有,按下“W”切换线框视角,按下“G”打开或关闭GUI组件。我们还可以自定义键盘事件和鼠标事件。
getKeyboardEvents
该方法能够返回一个字典,字典中为当前时刻被按下去的按键的ID以及它的状态。而pybullet中的键盘状态有三种:KEY_IS_DOWN, KEY_WAS_TRIGGERED 和 KEY_WAS_RELEASED。KEY_WAS_TRIGGERED 会在该按键刚刚被按下去后触发,并将按钮状态设为KEY_IS_DOWN;只要按键被一直按着,那么KEY_IS_DOWN就会一直触发;按钮松开,KEY_WAS_RELEASED会被触发。如果按键处在没有被按下去的状态,那么该按键就不会出现在getKeyboardEvents的返回值中。(这一块和doc上说的有点出入,但是我试下来确实如此)
所以啥都不按,getKeyboardEvents只会返回空字典。除了一些特殊的按键,一般的按键的ID就是它的小写字母对应的Unicode码。所以可以通过如下语句判断某个按钮是否处于KEY_IS_DOWN信号:
import pybullet as p
import pybullet_data
from time import sleep
use_gui = True
if use_gui:
cid = p.connect(p.GUI)
else:
cid = p.connect(p.DIRECT)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane_id = p.loadURDF("plane.urdf", useMaximalCoordinates=False)
robot_id = p.loadURDF("r2d2.urdf", basePosition=[0, 0, 0.5], useMaximalCoordinates=False)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
while True:
p.stepSimulation()
keys = p.getKeyboardEvents()
if ord("w") in keys and keys[ord("w")] & p.KEY_WAS_TRIGGERED:
print("w KEY_WAS_TRIGGERED")
elif ord("w") in keys and keys[ord("w")] & p.KEY_IS_DOWN:
print("w KEY_IS_DOWN")
elif ord("w") in keys and keys[ord("w")] & p.KEY_WAS_RELEASED:
print("w KEY_WAS_RELEASED")
p.disconnect(cid)
你可以试着按下这些按键,看看会打印出什么。
对于一些特殊的按键,它们可不存在Unicode码,所以它们的ID已经写成了一些常量:
说明 | 按键ID常量 |
---|---|
F1到F12 | B3G_F1 … B3G_F12 |
上下左右方向键 | B3G_LEFT_ARROW, B3G_RIGHT_ARROW, B3G_UP_ARROW, B3G_DOWN_ARROW |
同一页向上/下,页尾,起始页 | B3G_PAGE_UP, B3G_PAGE_DOWN, B3G_PAGE_END, B3G_HOME |
删除,插入,Alt,Shift,Ctrl,Enter,Backspace,空格 | B3G_DELETE, B3G_INSERT, B3G_ALT, B3G_SHIFT, B3G_CONTROL, B3G_RETURN, B3G_BACKSPACE, B3G_SPACE |
所以,我们可以通过这些按钮响应编写一套机制,使得用户与界面的交互更加容易。比如,我们可以在环境中编写一个简单的文本输入框,支持小写字母和数字的输入和回退:
import pybullet as p
import pybullet_data
from time import sleep
use_gui = True
if use_gui:
cid = p.connect(p.GUI)
else:
cid = p.connect(p.DIRECT)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane_id = p.loadURDF("plane.urdf", useMaximalCoordinates=False)
robot_id = p.loadURDF("r2d2.urdf", basePosition=[0, 0, 0.5], useMaximalCoordinates=False)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
text = [] # 存储文本框内容
# 先设置一个空内容
debug_text_id = p.addUserDebugText(
text="",
textPosition=[0, 0, 2],
textColorRGB=[0, 0, 1],
textSize=1.5
while True:
p.stepSimulation()
key_dict = p.getKeyboardEvents()
if len(key_dict):
print(key_dict)
# 如果有backspace,则删除text的最后一个字符,并重新渲染
if p.B3G_BACKSPACE in key_dict and key_dict[p.B3G_BACKSPACE] & p.KEY_WAS_TRIGGERED:
if len(text) != 0:
text.pop()
debug_text_id = p.addUserDebugText(
text="".join(text),
textPosition=[0, 0, 2],
textColorRGB=[0, 0, 1],
textSize=1.5,
replaceItemUniqueId=debug_text_id
else:
for k, v in key_dict.items():
if v & p.KEY_WAS_TRIGGERED: # 只考虑刚刚按下的按键
if ord("a") <= k <= ord("z"):
text.append(chr(k))
elif k == p.B3G_SPACE:
text.append(" ")
elif ord("0") <= k <= ord("9"):
text.append(chr(k))
debug_text_id = p.addUserDebugText(
text="".join(text),
textPosition=[0, 0, 2],
textColorRGB=[0, 0, 1],
textSize=1.5,
replaceItemUniqueId=debug_text_id
p.disconnect(cid)
out:
使用getKeyboardEvents控制机器人
除此之外,我们还可以使用这个方法控制机器人,就好像玩游戏一样,我们首先先得到四个轮子关节的名字和关节索引:
for i in range(p.getNumJoints(robot_id)):
if "wheel" in p.getJointInfo(robot_id, i)[1].decode("utf-8"):
print(p.getJointInfo(robot_id, i)[:2])
out:
(2, b'right_front_wheel_joint')
(3, b'right_back_wheel_joint')
(6, b'left_front_wheel_joint')
(7, b'left_back_wheel_joint')
接下来,我们将向左和向右通过差分驱动来完成,向前和向后就是四个轮子同向,左前和右前同样是差分驱动。
代码很简单,注意反向马达时,只有速度是负的,力永远是正的。
import pybullet as p
import pybullet_data
from time import sleep
use_gui = True
if use_gui:
cid = p.connect(p.GUI)
else:
cid = p.connect(p.DIRECT)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane_id = p.loadURDF("plane.urdf", useMaximalCoordinates=False)
robot_id = p.loadURDF("r2d2.urdf", basePosition=[0, 0, 0.5], useMaximalCoordinates=False)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
textColor = [1, 1, 0]
# 先设置一个空内容
debug_text_id = p.addUserDebugText(
text="",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5
maxV = 30
maxF = 30
t = 2 # 左前或右前的轮子的速度差的倍数
logging_id = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "./log/keyboard2.mp4")
while True:
p.stepSimulation()
key_dict = p.getKeyboardEvents()
if len(key_dict):
if p.B3G_UP_ARROW in key_dict and p.B3G_LEFT_ARROW in key_dict: # 左前
p.setJointMotorControlArray( # 2,3为右 6,7为左
bodyUniqueId=robot_id,
jointIndices=[2, 3],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[maxV, maxV],
forces=[maxF, maxF]
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[maxV / t, maxV / t],
forces=[maxF / t, maxF / t]
debug_text_id = p.addUserDebugText(
text="up + left",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
elif p.B3G_UP_ARROW in key_dict and p.B3G_RIGHT_ARROW in key_dict: # 右前
p.setJointMotorControlArray( # 2,3为右 6,7为左
bodyUniqueId=robot_id,
jointIndices=[6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[maxV, maxV],
forces=[maxF, maxF]
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[2, 3],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[maxV / t, maxV / t],
forces=[maxF / t, maxF / t]
debug_text_id = p.addUserDebugText(
text="up + right",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
elif p.B3G_UP_ARROW in key_dict: # 向前
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[2, 3, 6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[maxV, maxV, maxV, maxV],
forces=[maxF, maxF, maxF, maxF]
debug_text_id = p.addUserDebugText(
text="up",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
elif p.B3G_DOWN_ARROW in key_dict: # 向后
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[2, 3, 6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[-maxV / t, -maxV / t, -maxV / t, -maxV / t],
forces=[maxF / t, maxF / t, maxF / t, maxF / t]
debug_text_id = p.addUserDebugText(
text="down",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
elif p.B3G_LEFT_ARROW in key_dict: # 原地左转
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[2, 3, 6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[maxV / t, maxV / t, -maxV / t, -maxV / t],
forces=[maxF / t, maxF / t, maxF / t, maxF / t]
debug_text_id = p.addUserDebugText(
text="left",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
elif p.B3G_RIGHT_ARROW in key_dict: # 原地右转
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[2, 3, 6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[-maxV / t, -maxV / t, maxV / t, maxV / t],
forces=[maxF / t, maxF / t, maxF / t, maxF / t]
debug_text_id = p.addUserDebugText(
text="right",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
else: # 没有按键,则停下
p.setJointMotorControlArray(
bodyUniqueId=robot_id,
jointIndices=[2, 3, 6, 7],
controlMode=p.VELOCITY_CONTROL,
targetVelocities=[0, 0, 0, 0],
forces=[0, 0, 0, 0]
debug_text_id = p.addUserDebugText(
text="",
textPosition=[0, 0, 2],
textColorRGB=textColor,
textSize=2.5,
replaceItemUniqueId=debug_text_id
p.stopStateLogging(logging_id)
p.disconnect(cid)
out:
getMouseEvents
通过这个方法可以获取鼠标事件。类似于键盘事件,鼠标事件也只有三种状态:KEY_IS_DOWN, KEY_WAS_TRIGGERED 和 KEY_WAS_RELEASED。
getMouseEvents有一个可选参数,为服务器名,默认为0。返回值如下:
我们可以先随便试试:
import pybullet as p
import pybullet_data
from time import sleep
cid = p.connect(p.GUI)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane_id = p.loadURDF("plane.urdf", useMaximalCoordinates=False)
robot_id = p.loadURDF("r2d2.urdf", basePosition=[0, 0, 2],useMaximalCoordinates=False)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
while True:
p.stepSimulation()
mouse = p.getMouseEvents()
if len(mouse):
print(mouse)
p.disconnect(cid)
输出内容就不再展示了,你会发现,只有当你移动鼠标,或者点击鼠标时,才会有信息被打印出来。
需要注意的是,返回的只是二维坐标,想要将鼠标点击的地方转换成模拟器的空间内的坐标,需要一番操作,doc提供了 一个很有意思的例子 ,这个例子的演示如下:
可以看到,虽然鼠标事件返回的是二维的坐标信息,但是例子中我们却可以通过鼠标点击来改变物体的颜色,改变颜色是使用的changeVisualShape方法,这个简单,关键是怎么做才能使得我们的二维坐标变成物体的坐标,或者说,怎么做才能使得我们的鼠标的点击能够达到选中目标的功能?
其实很简单,只需要根据getDebugVisualizerCamera返回的参数得到目前我们的镜头的坐标,再结合水平角度得到鼠标点击位置,以此为参数进行激光探测,激光探测点到的物体就是我们实际想要选中的物体,根据rayTest返回的参数,我们就可以知道被命中的物体的ID了,那么我们也就获取了点击的物体。
doc给的例子中的函数实现了上面说的功能:
def getRayFromTo(mouseX, mouseY):
width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera(
camPos = [
camTarget[0] - dist * camForward[0],
camTarget[1] - dist * camForward[1],
camTarget[2] - dist * camForward[2]
farPlane = 10000
rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])]
invLen = farPlane * 1. / (math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] *
rayForward[1] + rayForward[2] * rayForward[2]))
rayForward = [invLen * rayForward[0], invLen * rayForward[1], invLen * rayForward[2]]
rayFrom = camPos
oneOverWidth = float(1) / float(width)
oneOverHeight = float(1) / float(height)
dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth]
dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight]
rayToCenter = [
rayFrom[0] + rayForward[0], rayFrom[1] + rayForward[1], rayFrom[2] + rayForward[2]
rayTo = [