2525import pybullet
2626
2727
28- def load_robot_description (
29- description_name : str ,
30- commit : Optional [ str ] = None ,
31- ) -> int :
32- """ Load a robot description in PyBullet.
28+ def load_robot_description (description_name : str ,
29+ basePosition = ( 0 , 0 , 0 ), baseOrientation = ( 0 , 0 , 0 , 1 ), flags = - 1 ,
30+ useFixedBase = 0 , physicsClientId = 0 , commit = None ) -> int :
31+ """
32+ Load a robot description in PyBullet.
3333
3434 Args:
3535 description_name: Name of the robot description.
36- commit: If specified, check out that commit from the cloned robot
37- description repository.
36+ basePosition: 3D position of the base of the robot in world coordinates.
37+ baseOrientation: orientation in quaternion (xyzw) of the base of the robot in world coordinates.
38+ flags: int flags for the URDF loading in pybullet.
39+ useFixedBase: boolean indicating use a fix joint between world and robot base.
40+ physicsClientId: int indicating the pybullet client id.
41+ commit: If specified, check out that commit from the cloned robot description repository.
3842
3943 Returns:
40- Identifier of the robot in PyBullet.
44+ Integer identifier of the robot in PyBullet.
4145 """
4246 if commit is not None :
4347 os .environ ["ROBOT_DESCRIPTION_COMMIT" ] = commit
@@ -46,5 +50,7 @@ def load_robot_description(
4650 raise ValueError (f"{ description_name } is not a URDF description" )
4751
4852 pybullet .setAdditionalSearchPath (module .PACKAGE_PATH )
49- robot = pybullet .loadURDF (module .URDF_PATH )
53+ robot = pybullet .loadURDF (module .URDF_PATH ,
54+ basePosition = basePosition , baseOrientation = baseOrientation , flags = flags ,
55+ useFixedBase = useFixedBase , physicsClientId = physicsClientId )
5056 return robot
0 commit comments