make the motorId corresponds to that of the real minitaur. change the mass of the quadruped.urdf, change the friction of plane.urdf.
This commit is contained in:
@@ -2,7 +2,7 @@
|
|||||||
<robot name="cube.urdf">
|
<robot name="cube.urdf">
|
||||||
<link name="planeLink">
|
<link name="planeLink">
|
||||||
<contact>
|
<contact>
|
||||||
<lateral_friction value="1.5"/>
|
<lateral_friction value="2"/>
|
||||||
</contact>
|
</contact>
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
|||||||
@@ -15,7 +15,7 @@
|
|||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1."/>
|
<mass value="3.2"/>
|
||||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|||||||
@@ -1,4 +1,5 @@
|
|||||||
import pybullet as p
|
import pybullet as p
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
class Minitaur:
|
class Minitaur:
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
@@ -8,7 +9,8 @@ class Minitaur:
|
|||||||
self.quadruped = p.loadURDF("quadruped/quadruped.urdf",0,0,.3)
|
self.quadruped = p.loadURDF("quadruped/quadruped.urdf",0,0,.3)
|
||||||
self.kp = 1
|
self.kp = 1
|
||||||
self.kd = 0.1
|
self.kd = 0.1
|
||||||
self.maxForce = 100
|
self.maxForce = 3.5
|
||||||
|
self.motorDir = [1, -1, 1, -1, -1, 1, -1, 1]
|
||||||
nJoints = p.getNumJoints(self.quadruped)
|
nJoints = p.getNumJoints(self.quadruped)
|
||||||
self.jointNameToId = {}
|
self.jointNameToId = {}
|
||||||
for i in range(nJoints):
|
for i in range(nJoints):
|
||||||
@@ -73,11 +75,12 @@ class Minitaur:
|
|||||||
return orientation
|
return orientation
|
||||||
|
|
||||||
def applyAction(self, motorCommands):
|
def applyAction(self, motorCommands):
|
||||||
self.setMotorAngleByName('motor_front_rightR_joint', motorCommands[0])
|
motorCommandsWithDir = np.multiply(motorCommands, self.motorDir)
|
||||||
self.setMotorAngleByName('motor_front_rightL_joint', motorCommands[1])
|
self.setMotorAngleByName('motor_front_leftR_joint', motorCommandsWithDir[0])
|
||||||
self.setMotorAngleByName('motor_front_leftR_joint', motorCommands[2])
|
self.setMotorAngleByName('motor_front_leftL_joint', motorCommandsWithDir[1])
|
||||||
self.setMotorAngleByName('motor_front_leftL_joint', motorCommands[3])
|
self.setMotorAngleByName('motor_back_leftR_joint', motorCommandsWithDir[2])
|
||||||
self.setMotorAngleByName('motor_back_rightR_joint', motorCommands[4])
|
self.setMotorAngleByName('motor_back_leftL_joint', motorCommandsWithDir[3])
|
||||||
self.setMotorAngleByName('motor_back_rightL_joint', motorCommands[5])
|
self.setMotorAngleByName('motor_front_rightL_joint', motorCommandsWithDir[4])
|
||||||
self.setMotorAngleByName('motor_back_leftR_joint', motorCommands[6])
|
self.setMotorAngleByName('motor_front_rightR_joint', motorCommandsWithDir[5])
|
||||||
self.setMotorAngleByName('motor_back_leftL_joint', motorCommands[7])
|
self.setMotorAngleByName('motor_back_rightL_joint', motorCommandsWithDir[6])
|
||||||
|
self.setMotorAngleByName('motor_back_rightR_joint', motorCommandsWithDir[7])
|
||||||
|
|||||||
@@ -21,7 +21,7 @@ def main(unused_args):
|
|||||||
for i in range(1000):
|
for i in range(1000):
|
||||||
a1 = math.sin(i*speed)*amplitude+1.57
|
a1 = math.sin(i*speed)*amplitude+1.57
|
||||||
a2 = math.sin(i*speed+3.14)*amplitude+1.57
|
a2 = math.sin(i*speed+3.14)*amplitude+1.57
|
||||||
joint_values = [a1, -1.57, a1, -1.57, a2, -1.57, a2, -1.57]
|
joint_values = [a1, 1.57, a2, 1.57, 1.57, a1, 1.57, a2]
|
||||||
minitaur.applyAction(joint_values)
|
minitaur.applyAction(joint_values)
|
||||||
|
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
|||||||
Reference in New Issue
Block a user