bulletphysics / bullet3

Bullet Physics SDK: real-time collision detection and multi-physics simulation for VR, games, visual effects, robotics, machine learning etc.
http://bulletphysics.org
Other
12.6k stars 2.87k forks source link

Issue with torque_control mode for franka panda robot #4635

Open SKYLEO98 opened 3 months ago

SKYLEO98 commented 3 months ago

Hello, I am encountering trouble implementing torque_control mode in Pybullet with Franka Panda. The robot could move to the initial position that I imply with position_control mode. However, I tried to run the torque_control mode for moving to swap whole joint range but it did not work. The robot just stays at its initial location. Is there any specifications to imply the torque_control mode in pybullet?

` import os import pybullet as p import pybullet_data import time import math import numpy as np

p.connect(p.GUI) p.setAdditionalSearchPath(pybullet_data.getDataPath()) p.setGravity(0,0,-9.81)

planeId = p.loadURDF("plane.urdf") startPos = [0,0,0] startOrientation = p.getQuaternionFromEuler([0,0,0]) robotPath= "/home/hoan/rl-baselines3-zoo/rl_zoo3/franka_urdf/panda.urdf" robotId = p.loadURDF(robotPath,startPos, startOrientation, useFixedBase=True)

timeStep = 0.001

p.setTimeStep(timeStep)

jointIds = []

maxForce =40

joint_set= [1, -1.53487, -1.67553, 0, -0.0625838, 1.7395, 0.684601] for i in range(6): p.setJointMotorControl2(robotId , i, p.POSITION_CONTROL,joint_set[i]) p.stepSimulation() joint_set= [87, 0, 0, -87, 0, 0, 0]

time.sleep(1) while True: p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING) for i in range(6): p.setJointMotorControl2(bodyIndex = robotId , jointIndex = i, controlMode = p.TORQUE_CONTROL, force = joint_set[i]) p.stepSimulation() time.sleep(1./240.)

currentPose = p.getBasePositionAndOrientation(robotId)
currentPosition = currentPose[0]
EOF_pos = p.getLinkState(robotId,11)[0]
print("EOF_pos",EOF_pos)
#print(currentPosition)
numJoint=p.getNumJoints(robotId)
for j in range(p.getNumJoints(robotId)):
    info=p.getJointInfo(robotId,j)
    linkState= p.getLinkState(robotId,2)[0]
    jointIndex = info[0]
    jointName = info[1]
    jointType = info[2]
    jointPos =info[3]
    jointName =info[12]
    stateJoint=p.getJointState(robotId,0)

    #print(jointName,jointType,jointPos,jointIndex)
    #print(p.getJointState(robotId,0)[1])
    #print(np.round(linkState,2))
    #jointIds.append(j)
p.stepSimulation()

`

yaswanth1701 commented 3 months ago

Hi there, you need to set p.setJointMotorControlArray(model_id,joints_index, p.VELOCITY_CONTROL, forces=np.zeros(num_joints)) to enable torque control which is not enabled by default. Please refer to the documentation for more details here.

SKYLEO98 commented 3 months ago

Hi there, you need to set p.setJointMotorControlArray(model_id,joints_index, p.VELOCITY_CONTROL, forces=np.zeros(num_joints)) to enable torque control which is not enabled by default. Please refer to the documentation for more details here.

Thank @yaswanth1701. It was solved following your suggestion. I could not find this decent setting in the online documentation.

yaswanth1701 commented 3 months ago

That sounds great.