一、引言
pybullet是一个机器人研究中常用的仿真引擎,在使用pybullet时,为了能够更好地控制机器人执行相应的动作,通常需要进行一些必要的设置,比如设置重力等等。那今天我们来看一下pybullet中关于运动的一些接口函数设置,了解下这个接口函数的作用及设置方式吧。
二、接口函数
1、动作平滑渲染
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING) #平滑视觉渲染
注意这句话只能用在每次step函数的开头,也就是说,在运动的之前,运动这句话,就会对每次运动进行平滑。不可以加在init里,那样是没有效果的。而这句话也不会对运动产生丝毫影响,除了影响渲染环境中机械臂运动的速度。
这两个输出分别是在step中加了这句话和不加时,一次运动后得到的结果(运动为位置的x轴加了点位移),可以发现完全一样。
可以看到,两者完全没有区别。
2、逆运动学求解次数
当我们在使用逆运动学求解器的时候,如果迭代求解的次数,不够的话,是不能得到准确的关节角的。在仿真次数为100次(下面介绍)时,当我们测试迭代求解次数分别时10和100时,x轴增加0.001时,运动一次后,末端的位置。
可以很明显得看到,随着次数的增加,位置越来越精准。
3、仿真次数
当我们运行
p.stepSimulation()
时,便意味着进行了一次仿真时间内的运动。每次运动的距离可能不是一次仿真时间可以解决的,下面测试1,10,100次仿真时间时,位置精度情况(逆运动学100次求解时)
可以看到随着仿真次数的增减,精度也在不断提高。
三、代码
# _*_coding:utf-8-*-
import sys
import gym
from gym import spaces
import pybullet as p
import pybullet_data
import math
import numpy as np
import argparse
from env_module import random_pos, random_position, get_position_r, get_position_p, quaternion_revised, admittance
gym.logger.set_level(40)
class UREnv(gym.Env):
metadata = {'render.modes': ['human']}
def __init__(self, gui=False):
if gui:
p.connect(p.GUI)
else:
p.connect(p.DIRECT)
p.resetDebugVisualizerCamera(cameraDistance=0.3, cameraYaw=60, cameraPitch=-50,
cameraTargetPosition=[0.5, -0.05, 0.1])
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.setGravity(0, 0, -10)
def step(self):
# p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING) #平滑视觉渲染
self.posture = np.array(p.getLinkState(self.pandauid, 6)[5],dtype=float).reshape(4,1)
self.position = np.array(p.getLinkState(self.pandauid, 6)[4],dtype=float).reshape(3,1)
print(self.position[0])
self.position[0] = float(self.position[0])+0.001
# print(self.position[0])
jointposes = p.calculateInverseKinematics(self.pandauid, 6, self.position, self.posture, maxNumIterations=100)
p.setJointMotorControlArray(self.pandauid, list([1, 2, 3, 4, 5, 6]), p.POSITION_CONTROL, list(jointposes))
n=100
while(n):
p.stepSimulation()
n = n-1
self.position = np.array(p.getLinkState(self.pandauid, 6)[4],dtype=float).reshape(3,1)
print(self.position[0])
# print("加了平滑")
# print("没加平滑")
# print("2次迭代")
# print("10次迭代")
# print("100次迭代")
# print("1次仿真")
# print("10次仿真")
print("100次仿真")
def reset(self):
p.resetSimulation()
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.loadURDF("plane.urdf", basePosition=[0, 0, -0.65])
self.pandauid = p.loadURDF("ur5_10cm_10mm.urdf", useFixedBase=True)
p.loadURDF("table/table.urdf", basePosition=[0.5, 0, -0.65])
orientation = p.getQuaternionFromEuler([math.pi / 2., -math.pi, 0])
p.loadURDF("12mm/urdf/hole.urdf", basePosition=[0.355, 0, 0], baseOrientation=orientation,
useFixedBase=True)
rest_poses = [0.019493980630576238, -1.6104386316325356, 2.371476945587111, -2.3317793248031182,
-1.57079440431533, 0]
for j in range(6):
p.resetJointState(self.pandauid, j + 1, rest_poses[j])
p.stepSimulation()
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
def close(self):
p.disconnect()
if __name__ == '__main__':
U = UREnv()
U.reset()
m = 1
while(m):
m = m-1
U.step()
U.close()
May the force be with you!
评论(0)
您还未登录,请登录后发表或查看评论