pycram.ros_utils.object_state_updater
=====================================

.. py:module:: pycram.ros_utils.object_state_updater


Classes
-------

.. autoapisummary::

   pycram.ros_utils.object_state_updater.RobotStateUpdater
   pycram.ros_utils.object_state_updater.EnvironmentStateUpdater


Module Contents
---------------

.. py:class:: RobotStateUpdater(tf_topic: str, joint_state_topic: str)

   Updates the robot in the World with information of the real robot published to ROS topics.
   Infos used to update the robot are:

       * The current pose of the robot
       * The current joint state of the robot
   .. Note:: This class can only be used if the topics are present in the RSO network on the real robot/world,
   hence it is not testable in the CI.


   .. py:attribute:: tf_listener


   .. py:attribute:: tf_topic


   .. py:attribute:: joint_state_topic


   .. py:attribute:: tf_timer


   .. py:attribute:: joint_state_timer


   .. py:method:: _subscribe_tf(msg: geometry_msgs.msg.TransformStamped) -> None

      Callback for the TF timer, will do a lookup of the transform between map frame and the robot base frame.

      :param msg: TransformStamped message published to the topic



   .. py:method:: _subscribe_joint_state(msg: sensor_msgs.msg.JointState) -> None

      Sets the current joint configuration of the robot in the world to the configuration published on the
      topic. Since this uses rospy.wait_for_message which can have errors when used with threads there might be an
      attribute error in the rospy implementation.

      :param msg: JointState message published to the topic.



   .. py:method:: _stop_subscription() -> None

      Stops the Timer for TF and joint states and therefore the updating of the robot in the world.



.. py:class:: EnvironmentStateUpdater(tf_topic: str, joint_state_topic: str)

   Updates the environment in the World with information of the real environment published to ROS topics.
   Infos used to update the envi are:
       * The current pose of the environment
       * The current joint state of the environment

   .. Note:: This class can only be used if the topics are present in the RSO network on the real robot/world,
   hence it is not testable in the CI.


   .. py:attribute:: tf_listener


   .. py:attribute:: tf_topic


   .. py:attribute:: joint_state_topic


   .. py:attribute:: joint_state_timer


   .. py:method:: _subscribe_joint_state(msg: sensor_msgs.msg.JointState) -> None

      Sets the current joint configuration of the environment in the world to the configuration published on the topic.
      Since this uses rospy.wait_for_message which can have errors when used with threads there might be an attribute error
      in the rospy implementation.

      :param msg: JointState message published to the topic.



   .. py:method:: _stop_subscription() -> None

      Stops the Timer for TF and joint states and therefore the updating of the environment in the world.



