pyrcf.components.robot_interfaces.simulation.pybullet_robot =========================================================== .. py:module:: pyrcf.components.robot_interfaces.simulation.pybullet_robot Classes ------- .. autoapisummary:: pyrcf.components.robot_interfaces.simulation.pybullet_robot.PybulletRobot Module Contents --------------- .. py:class:: PybulletRobot(urdf_path: str, ee_names: List[str] = None, place_on_ground: bool = True, default_base_position: numpy.ndarray = np.zeros(3), default_base_orientation: numpy.ndarray = np.array([0, 0, 0, 1]), default_joint_positions: numpy.ndarray = None, create_pinocchio_interface: bool = True, floating_base: bool = True, verbose: bool = True, **sim_interface_kwargs) Bases: :py:obj:`pyrcf.components.robot_interfaces.simulation.sim_robot_base.SimulatedRobotInterface` A RobotInterface implementation for a generic robot in pybullet. All subclasses of this method will use synchronous sim time stepping, i.e. the simulated world will step only when the read() method of this class is called. This is to keep the clock synchronous and for providing full repeatable performance to the control loop by minimising parallelisation. .. py:attribute:: DEFAULT_URDF_PATH :type: str :value: None Default urdf path to be used for particular instances of PybulletRobot. This variable should be overridden in the implemented child classes. .. py:class:: BulletWorldClock(dt: float) Bases: :py:obj:`pyrcf.utils.time_utils.ClockBase` Only valid if sim stepping is done synchronously and managed by the PybulletRobot class. .. py:attribute:: _current_t :value: 0.0 .. py:attribute:: _dt .. py:method:: step_time() To be called each time simulation steps forward. .. py:method:: get_time() -> float Get the latest time from this clock. :raises NotImplementedError: Raised if this method is not implemented by the child class. :returns: the current time in seconds. :rtype: float .. py:attribute:: _sim_robot .. py:attribute:: _clock .. py:method:: read() -> pyrcf.core.types.RobotState Get the latest state from the robot. :raises NotImplementedError: Raised if this method is not implemented by the child class. :returns: the latest state of the robot. :rtype: RobotState .. py:method:: write(cmd: pyrcf.core.types.RobotCmd) -> bool Send the specified commands to the robot. :param cmd: the command object as computed by the controller in the loop. :type cmd: RobotCmd :raises NotImplementedError: Raised if this method is not implemented by the child class. :returns: True if sending command was succesful. :rtype: bool .. py:method:: set_base_pose(position: numpy.ndarray, orientation: pyrcf.core.types.QuatType) Set the pose of the base of the simulated robot in the world frame. :param position: Desired position for the base frame in the world. :type position: np.ndarray :param orientation: Desired orientation quaternion [x,y,z,w] for base frame in the world. :type orientation: QuatType :raises NotImplementedError: Raised if this method is not implemented by the child class. .. py:method:: get_sim_clock() -> pyrcf.utils.time_utils.ClockBase Get the Clock object that gives the time in this simulated world. :raises NotImplementedError: Raised if this method is not implemented by the child class. :returns: The Clock object that can be used to get the current time using its get_time() method. :rtype: ClockBase .. py:method:: shutdown() Cleanly shutdown the PyRCF component. Override in child class if required. The base class implements an empty function. .. py:method:: withJointsLocked(joints_to_lock: Mapping[str, float] = None, temp_urdf: bool = True, **kwargs) :classmethod: Classmethod for RobotInterface implementation for PybulletRobot robot in pybullet, that locks the specified joints of the robot. All specified joints are converted to "fixed" joint type and cannot be reverted dynamically! NOTE: Use this method with caution. All keyword arguments are directly passed to the default constructor! :param joints_to_lock: Dictionary containing name of joints that should be locked as keys, and the joint values to lock them at as values. By default, uses upper body joints (from upper torso upwards) set to zeros. :type joints_to_lock: Mapping[str, float] :param temp_urdf: If set to True, will create a temporary urdf that will be deleted after loading in pybullet, otherwise create a file in /tmp/ directory. Defaults to True. :type temp_urdf: bool, optional :param \*\*kwargs: additional keyword arguments to pass to PybulletRobot or subclass. ------------------------------------------------------------------------------------------- .. note:: By default, the urdf created via this constructor is only valid during construction. The path to the urdf (accessed through self._sim_robot.urdf_path, for instance) will not be a valid path once the init is completed. This is because this method temporarily creates a urdf after modifying the specified joints to "fixed" joint type, and destroys the temporary file soon after all objects using it (pybullet, pinocchio, etc.) are created in the construction. To disable this behaviour, set `temp_urdf=False` during construction. This will create a permenant urdf file in the /tmp/ directory. ------------------------------------------------------------------------------------------- .. py:method:: fromAwesomeRobotDescriptions(robot_description_name: str, ee_names: List[str] = None, place_on_ground: bool = True, default_base_position: numpy.ndarray = np.zeros(3), default_base_orientation: numpy.ndarray = np.array([0, 0, 0, 1]), default_joint_positions: numpy.ndarray = None, create_pinocchio_interface: bool = True, floating_base: bool = True, verbose: bool = True, **sim_interface_kwargs) -> PybulletRobot :classmethod: Create a PybulletRobot instance using robots available in the open source Awesome Robot Descriptions list (https://github.com/robot-descriptions/robot_descriptions.py/tree/main?tab=readme-ov-file#descriptions). The list of available robot descriptions can also be viewed in the variable `AWESOME_ROBOTS` imported from `pybullet_robot.utils.urdf_utils`. Downloads description package for the specified robot and caches it locally (only needs downloading once), and loads this robot as a PybulletRobot instance. NOTE: `ee_names` should be provided if proper end-effector kinematics is required. Also starting pose and joint configurations are always at zero. So to set to some specific configuration provide appropriate arguments. :param robot_description_name: The name of the robot description package name. Should be a value available in the awesome robots list (also defined in variable `AVAILABLE_ROBOTS` in `utils.urdf_utils`). :type robot_description_name: str :param ee_names: List of end-effectors for the robot. Defaults to None. :type ee_names: List[str], optional :param place_on_ground: If true, the base position height will automatically be adjusted such that the robot is on the ground with the given joint positions. Defaults to True. :type place_on_ground: bool :param default_base_position: Default position of the base of the robot in the world frame during start-up. Note that the height value (z) is only used if 'place_on_ground' is set to False. Defaults to np.zeros(3). :type default_base_position: np.ndarray, optional :param default_base_orientation: Default orientation quaternion in the world frame for the base of the robot during start-up. Defaults to np.array([0, 0, 0, 1]). :type default_base_orientation: np.ndarray, optional :param default_joint_positions: Optional starting values for joints. Defaults to None. NOTE: These values should be in the order of joints in pybullet. :type default_joint_positions: List[float], optional :param create_pinocchio_interface: If true, creates a PinocchioInterface object for this robot. The object is automatically updated with latest state when read() is called. Defaults to True. :type create_pinocchio_interface: bool, optional :param floating_base: Specifying whether this robot has a floating or fixed base (setting to True creates a floating base instance with pinocchio, and makes the simulated robot free floating (not fixed base)). Defaults to True. :type floating_base: bool, optional :param verbose: Verbosity flag for debugging robot info during construction. Defaults to True. :type verbose: bool, optional :returns: A PybulletRobot instance created using the URDF generated using the awesome robot descriptions package. :rtype: PybulletRobot