mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-15 06:00:12 +00:00
255 lines
18 KiB
Plaintext
255 lines
18 KiB
Plaintext
|
{
|
||
|
"cells": [
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 1,
|
||
|
"metadata": {
|
||
|
"collapsed": true
|
||
|
},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"import pybullet as p"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 2,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"text/plain": [
|
||
|
"0"
|
||
|
]
|
||
|
},
|
||
|
"execution_count": 2,
|
||
|
"metadata": {},
|
||
|
"output_type": "execute_result"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"p.connect(p.DIRECT)"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 3,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"text/plain": [
|
||
|
"0"
|
||
|
]
|
||
|
},
|
||
|
"execution_count": 3,
|
||
|
"metadata": {},
|
||
|
"output_type": "execute_result"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"p.loadURDF(\"plane.urdf\")"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 4,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"r2d2=p.loadURDF(\"r2d2.urdf\",[0,0,0.5])"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 5,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"text/plain": [
|
||
|
"2"
|
||
|
]
|
||
|
},
|
||
|
"execution_count": 5,
|
||
|
"metadata": {},
|
||
|
"output_type": "execute_result"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"p.getNumBodies()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 6,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stdout",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"joint 0 name= base_to_right_leg\n",
|
||
|
"joint 1 name= right_base_joint\n",
|
||
|
"joint 2 name= right_front_wheel_joint\n",
|
||
|
"joint 3 name= right_back_wheel_joint\n",
|
||
|
"joint 4 name= base_to_left_leg\n",
|
||
|
"joint 5 name= left_base_joint\n",
|
||
|
"joint 6 name= left_front_wheel_joint\n",
|
||
|
"joint 7 name= left_back_wheel_joint\n",
|
||
|
"joint 8 name= gripper_extension\n",
|
||
|
"joint 9 name= left_gripper_joint\n",
|
||
|
"joint 10 name= left_tip_joint\n",
|
||
|
"joint 11 name= right_gripper_joint\n",
|
||
|
"joint 12 name= right_tip_joint\n",
|
||
|
"joint 13 name= head_swivel\n",
|
||
|
"joint 14 name= tobox\n"
|
||
|
]
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"for i in range (p.getNumJoints(r2d2)):\n",
|
||
|
" jointInfo=p.getJointInfo(r2d2,i)\n",
|
||
|
" print(\"joint\",jointInfo[0],\"name=\",jointInfo[1].decode('ascii'))"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 7,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stdout",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"pos = 0.00000,0.00000,0.50000 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49983 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49948 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49896 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49826 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49740 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49636 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49514 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49375 \n",
|
||
|
"pos = 0.00000,-0.00000,0.49219 \n"
|
||
|
]
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"p.setGravity(0,0,-10)\n",
|
||
|
"precision=5\n",
|
||
|
"for i in range (10):\n",
|
||
|
" pos,orn = p.getBasePositionAndOrientation(r2d2)\n",
|
||
|
" posmsg='pos = {posx:.{prec}f},{posy:.{prec}f},{posz:.{prec}f} '.format(posx=pos[0],posy=pos[1],posz=pos[2], prec=precision)\n",
|
||
|
" print(posmsg)\n",
|
||
|
" p.stepSimulation()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 8,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"p.stepSimulation()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 9,
|
||
|
"metadata": {
|
||
|
"collapsed": true
|
||
|
},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"%matplotlib inline\n",
|
||
|
"\n",
|
||
|
"import matplotlib\n",
|
||
|
"import numpy as np\n",
|
||
|
"import matplotlib.pyplot as plt"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 12,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"camTargetPos = [0,0,0]\n",
|
||
|
"cameraUp = [0,0,1]\n",
|
||
|
"cameraPos = [1,1,1]\n",
|
||
|
"\n",
|
||
|
"pitch = -10.0\n",
|
||
|
"yaw = 60\n",
|
||
|
"roll=0\n",
|
||
|
"upAxisIndex = 2\n",
|
||
|
"camDistance = 4\n",
|
||
|
"pixelWidth = 320\n",
|
||
|
"pixelHeight = 200\n",
|
||
|
"nearPlane = 0.01\n",
|
||
|
"farPlane = 100\n",
|
||
|
"fov = 60\n",
|
||
|
"viewMatrix = p.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)\n",
|
||
|
"aspect = pixelWidth / pixelHeight;\n",
|
||
|
"projectionMatrix = p.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);\n",
|
||
|
"img_arr = p.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1])\n"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 13,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"image/png": "iVBORw0KGgoAAAANSUhEUgAAAXoAAAD0CAYAAACVbe2MAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nCoduyuCEk0/3Kz55DTC
|
||
|
"text/plain": [
|
||
|
"<matplotlib.figure.Figure at 0x108feb4a8>"
|
||
|
]
|
||
|
},
|
||
|
"metadata": {},
|
||
|
"output_type": "display_data"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"w=img_arr[0] #width of the image, in pixels\n",
|
||
|
"h=img_arr[1] #height of the image, in pixels\n",
|
||
|
"rgb=img_arr[2] #color data RGB\n",
|
||
|
"plt.imshow(rgb,interpolation='none')\n",
|
||
|
"plt.draw()\n",
|
||
|
"plt.show()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": null,
|
||
|
"metadata": {
|
||
|
"collapsed": true
|
||
|
},
|
||
|
"outputs": [],
|
||
|
"source": []
|
||
|
}
|
||
|
],
|
||
|
"metadata": {
|
||
|
"kernelspec": {
|
||
|
"display_name": "Python 3",
|
||
|
"language": "python",
|
||
|
"name": "python3"
|
||
|
},
|
||
|
"language_info": {
|
||
|
"codemirror_mode": {
|
||
|
"name": "ipython",
|
||
|
"version": 3
|
||
|
},
|
||
|
"file_extension": ".py",
|
||
|
"mimetype": "text/x-python",
|
||
|
"name": "python",
|
||
|
"nbconvert_exporter": "python",
|
||
|
"pygments_lexer": "ipython3",
|
||
|
"version": "3.6.1"
|
||
|
}
|
||
|
},
|
||
|
"nbformat": 4,
|
||
|
"nbformat_minor": 2
|
||
|
}
|