pycram.ros_utils.robot_state_updater#

Classes#

WorldStateUpdater

Updates the robot in the World with information of the real robot published to ROS topics.

Module Contents#

class pycram.ros_utils.robot_state_updater.WorldStateUpdater(tf_topic: str, joint_state_topic: str, update_rate: datetime.timedelta = timedelta(milliseconds=100), world: typing_extensions.Optional[pycram.datastructures.world.World] = None)#

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

tf_listener#
tf_topic#
joint_state_topic#
world: typing_extensions.Optional[pycram.datastructures.world.World] = None#
tf_timer#
joint_state_timer#
_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 objects frames.

Parameters:

msg – TransformStamped message published to the topic

_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.

Parameters:

msg – JointState message published to the topic.

_stop_subscription() None#

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