pyrobosim_ros.ros_interface.WorldROSWrapper.__init__
- WorldROSWrapper.__init__(world=None, name='pyrobosim', num_threads=2, state_pub_rate=0.1, dynamics_rate=0.01, dynamics_latch_time=0.5, dynamics_ramp_down_time=0.5, dynamics_enable_collisions=True)
Creates a ROS 2 world wrapper node.
- This node will:
Subscribe to single actions on the
commanded_action
topic.Subscribe to task plans on the
commanded_plan
topic.Subscribe to robot velocity commands on the
robot_name/cmd_vel
topic.Publish robot states on the
robot_name/robot_state
topic.Serve a
request_world_state
service to retrieve the world state for planning.
- Parameters:
world (
pyrobosim.core.world.World
) – World model instance.name (str) – Node name, defaults to
"pyrobosim"
.num_threads (int) – Number of threads in the multi-threaded executor. Defaults to number of CPUs on the host OS.
state_pub_rate (float) – Rate, in seconds, to publish robot state.
dynamics_rate (float) – Rate, in seconds, to update dynamics.
dynamics_latch_time (float) – Time, in seconds, to latch the latest published velocity commands for a robot.
dynamics_ramp_down_time (float) – Time, in seconds, to ramp down the velocity command to zero. This is applied after the latch time expires.
dynamics_enable_collisions (bool) – If true (default), enables collision checking when updating robot dynamics.