in ml3/envs/bullet_sim.py [0:0]
def apply_joint_torque(self, torque):
self.grav_comp = self.inverse_dynamics([0] * self.action_dim)
torque = torque + self.grav_comp
full_torque = torque.copy()
#torque = torque.clip(-self.torque_limits, self.torque_limits)
self.sim.setJointMotorControlArray(bodyIndex=self.robot_id,
jointIndices=self.controlled_joints,
controlMode=pybullet.TORQUE_CONTROL,
forces=torque)
self.sim.stepSimulation()
cur_joint_states = self.sim.getJointStates(self.robot_id, self.controlled_joints)
cur_joint_angles = [cur_joint_states[i][0] for i in range(self.n_dofs)]
cur_joint_vel = [cur_joint_states[i][1] for i in range(self.n_dofs)]
next_state = cur_joint_angles + cur_joint_vel
ls = list(self.sim.getLinkState(self.robot_id, self.ee_idx)[0])
self.cur_joint_pos = self.get_current_joint_pos()
self.cur_joint_vel = self.get_current_joint_vel()
self.curr_ee = self.get_current_ee_state()
return np.hstack([self.cur_joint_pos,self.cur_joint_vel]),self.curr_ee