Isaac Sim Version
4.5.0
4.2.0
4.1.0
4.0.0
4.5.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):
Operating System
Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify):
GPU Information
- Model: GeForce RTX 4070
- Driver Version: 550.54.14
Topic Description
Detailed Description
I’m trying to implement a Carter robot example for the ROS2 Navigation2 package as a standalone Python script. I wrote the Carter robot’s action graph in a Python file and executed it as a standalone workflow. I confirmed that the camera, LiDAR, and clock data are being published correctly. However, when I try to check if the /tf
data is being published properly by executing the command ros2 topic echo /tf
, the standalone Python file is forcibly terminated with a “Segmentation fault (core dumped)”. Similarly, when I run rviz2, the same segfault occurs and the Python file is forcibly terminated. If I remove the problematic command, the code runs without segfaults, but since the tf topic is essential for using the Navigation2 package, I need a solution for this issue.
Steps to Reproduce
- Save the attached code as a Python file
- Run the file (
./python.sh standalone_examples/api/isaacsim.ros2.bridge/ROS2_navigation2.py
) - In another terminal, execute
ros2 topic echo /tf
- Observe that the Python script terminates with a segfault error
Error Messages
Segmentation fault (core dumped)
Additional Information
What I’ve Tried
If I remove the og.Controller.evaluate(ros_odom_graph)
command from the code, the segfault problem does not occur, but then the /tf
data is not published, making it impossible to use the Navigation2 package.
Additional Context
The issue appears to be related to the TF tree and odometry data publishing graph. Specifically, the segfault occurs when the await og.Controller.evaluate(ros_odom_graph)
command is executed in the run_graph_evaluation()
function. The other graphs (clock, camera, LiDAR, Twist) work without any issues.
My python file
#!/usr/bin/env python3
import sys
import asyncio
import numpy as np
import rclpy
import time
import threading
import sensor_msgs.msg as sensor_msgs
import std_msgs.msg as std_msgs
from rclpy.node import Node
from builtin_interfaces.msg._time import Time
from astropy.coordinates import spherical_to_cartesian
from nav_msgs.msg import Odometry
from tf2_msgs.msg import TFMessage
from isaacsim import SimulationApp
CONFIG = {"renderer": "RaytracedLighting", "headless": False}
simulation_app = SimulationApp(CONFIG)
from isaacsim.core.utils.extensions import enable_extension
# Enable ROS bridge extension
enable_extension("isaacsim.ros2.bridge")
enable_extension("omni.graph.core")
enable_extension("omni.graph.action")
simulation_app.update()
import carb
import omni
import omni.graph.core as og
import usdrt.Sdf
import omni.replicator.core as rep
from isaacsim.core.api import SimulationContext
from isaacsim.core.utils import stage
from isaacsim.storage.native import get_assets_root_path
from omni.kit.viewport.utility import get_active_viewport
from pxr import Gf, Usd, UsdGeom, UsdShade, Sdf
from omni.isaac.core.utils.prims import is_prim_path_valid
# Locate Isaac Sim assets folder to load environment and robot stages
assets_root_path = get_assets_root_path()
if assets_root_path is None:
carb.log_error("Could not find Isaac Sim assets folder")
simulation_app.close()
sys.exit()
BACKGROUND_STAGE_PATH = "/Environment"
BACKGROUND_USD_PATH = "/Isaac/Environments/Simple_Warehouse/warehouse_with_forklifts.usd"
# Define the robot USD file path and stage path to load the robot.
ROBOT_USD_PATH = "/Isaac/Robots/Carter/nova_carter_sensors.usd"
ROBOT_STAGE_PATH = "/Nova_Carter_ROS"
# Basic environment setup
usd_stage = omni.usd.get_context().get_stage()
# Load the warehouse environment
stage.add_reference_to_stage(assets_root_path + BACKGROUND_USD_PATH, BACKGROUND_STAGE_PATH)
# Add the robot asset.
stage.add_reference_to_stage(assets_root_path + ROBOT_USD_PATH, ROBOT_STAGE_PATH)
robot_prim = omni.usd.get_context().get_stage().GetPrimAtPath(ROBOT_STAGE_PATH)
xformable = UsdGeom.Xformable(robot_prim)
# Clear all existing transform operations.
xformable.ClearXformOpOrder()
# Add a new translate operation.
translate_op = xformable.AddTranslateOp()
translate_op.Set(Gf.Vec3d(-6, -1, 0))
# Add a new rotate operation (in RotateXYZ order).
rotate_op = xformable.AddRotateXYZOp()
rotate_op.Set((0, 0, 180))
simulation_app.update()
# Create a graph for publishing clock information.
ROS_ClOCK_GRAPH_PATH = "/ROS_Clock"
clock_keys = og.Controller.Keys
(ros_clock_graph, _, _, _) = og.Controller.edit(
{
"graph_path": ROS_ClOCK_GRAPH_PATH,
"evaluator_name": "execution",
"pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
},
{
clock_keys.CREATE_NODES: [
("on_playback_tick", "omni.graph.action.OnPlaybackTick"),
("isaac_read_simulation_time", "isaacsim.core.nodes.IsaacReadSimulationTime"),
("ros2_publish_clock", "isaacsim.ros2.bridge.ROS2PublishClock"),
("ros2_context", "isaacsim.ros2.bridge.ROS2Context"),
],
clock_keys.CONNECT: [
("on_playback_tick.outputs:tick", "ros2_publish_clock.inputs:execIn"),
("ros2_context.outputs:context", "ros2_publish_clock.inputs:context"),
("isaac_read_simulation_time.outputs:simulationTime", "ros2_publish_clock.inputs:timeStamp"),
],
clock_keys.SET_VALUES: [
("ros2_context.inputs:domain_id", 0),
("ros2_publish_clock.inputs:topicName", "clock"),
],
},
)
# Create a graph for publishing camera information (depth, RGB, and camera info).
FRONT_HAWK_PATH = "/Nova_Carter_ROS/front_hawk"
FRONT_LEFT_CAMERA_PATH = "/Nova_Carter_ROS/chassis_link/front_hawk/left/camera_left"
front_hawk_keys = og.Controller.Keys
(front_hawk_graph, _, _, _) = og.Controller.edit(
{
"graph_path": FRONT_HAWK_PATH,
"evaluator_name": "execution",
"pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
},
{
front_hawk_keys.CREATE_NODES: [
("on_playback_tick", "omni.graph.action.OnPlaybackTick"),
("ros2_context", "isaacsim.ros2.bridge.ROS2Context"),
("left_camera_render_product", "isaacsim.core.nodes.IsaacCreateRenderProduct"),
("left_camera_publish_image", "isaacsim.ros2.bridge.ROS2CameraHelper"),
("left_camera_frame_id", "omni.graph.nodes.ConstantString"),
("isaac_run_one_simulation_frame", "isaacsim.core.nodes.OgnIsaacRunOneSimulationFrame"),
("camera_namespace", "omni.graph.nodes.ConstantString"),
("ros2_camera_info_helper", "isaacsim.ros2.bridge.ROS2CameraInfoHelper"),
("ros2_qos_profile", "isaacsim.ros2.bridge.ROS2QoSProfile"),
],
front_hawk_keys.CONNECT: [
("on_playback_tick.outputs:tick", "isaac_run_one_simulation_frame.inputs:execIn"),
("isaac_run_one_simulation_frame.outputs:step", "left_camera_render_product.inputs:execIn"),
("left_camera_render_product.outputs:execOut", "left_camera_publish_image.inputs:execIn"),
("left_camera_render_product.outputs:execOut", "ros2_camera_info_helper.inputs:execIn"),
("left_camera_render_product.outputs:renderProductPath", "left_camera_publish_image.inputs:renderProductPath"),
("left_camera_render_product.outputs:renderProductPath", "ros2_camera_info_helper.inputs:renderProductPath"),
("camera_namespace.inputs:value", "ros2_camera_info_helper.inputs:nodeNamespace"),
("camera_namespace.inputs:value", "left_camera_publish_image.inputs:nodeNamespace"),
("left_camera_frame_id.inputs:value", "ros2_camera_info_helper.inputs:frameId"),
("left_camera_frame_id.inputs:value", "left_camera_publish_image.inputs:frameId"),
("ros2_context.outputs:context", "ros2_camera_info_helper.inputs:context"),
("ros2_context.outputs:context", "left_camera_publish_image.inputs:context"),
("ros2_qos_profile.outputs:qosProfile", "ros2_camera_info_helper.inputs:qosProfile"),
("ros2_qos_profile.outputs:qosProfile", "left_camera_publish_image.inputs:qosProfile"),
],
front_hawk_keys.SET_VALUES: [
("camera_namespace.inputs:value", "/front_stereo_camera"),
("left_camera_frame_id.inputs:value", "map"),
("ros2_context.inputs:domain_id", 0),
("left_camera_render_product.inputs:cameraPrim", [Sdf.Path(FRONT_LEFT_CAMERA_PATH)]),
("left_camera_render_product.inputs:height", 1200),
("left_camera_render_product.inputs:width", 1920),
("left_camera_publish_image.inputs:topicName", "left/image_raw"),
("left_camera_publish_image.inputs:type", "rgb"),
("ros2_camera_info_helper.inputs:topicName", "left/camera_info"),
],
},
)
# Create a graph for publishing LiDAR information (/scan).
ROS_LIDAR_PATH = "/Nova_Carter_ROS/ros_lidars"
LIDAR_PATH = "/Nova_Carter_ROS/chassis_link/XT_32/PandarXT_32_10hz"
lidar_keys = og.Controller.Keys
(ros_lidar_graph, _, _, _) = og.Controller.edit(
{
"graph_path": ROS_LIDAR_PATH,
"evaluator_name": "execution",
"pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
},
{
lidar_keys.CREATE_NODES: [
("on_playback_tick", "omni.graph.action.OnPlaybackTick"),
("ros2_context", "isaacsim.ros2.bridge.ROS2Context"),
("front_3d_lidar_render_product", "isaacsim.core.nodes.IsaacCreateRenderProduct"),
("publish_front_3d_lidar_scan", "isaacsim.ros2.bridge.ROS2RtxLidarHelper"),
("isaac_run_one_simulation_frame", "isaacsim.core.nodes.OgnIsaacRunOneSimulationFrame"),
("node_namespace", "omni.graph.nodes.ConstantString"),
("ros2_qos_profile", "isaacsim.ros2.bridge.ROS2QoSProfile"),
],
lidar_keys.CONNECT: [
("on_playback_tick.outputs:tick", "isaac_run_one_simulation_frame.inputs:execIn"),
("isaac_run_one_simulation_frame.outputs:step", "front_3d_lidar_render_product.inputs:execIn"),
("front_3d_lidar_render_product.outputs:execOut", "publish_front_3d_lidar_scan.inputs:execIn"),
("front_3d_lidar_render_product.outputs:renderProductPath", "publish_front_3d_lidar_scan.inputs:renderProductPath"),
("node_namespace.inputs:value", "publish_front_3d_lidar_scan.inputs:nodeNamespace"),
("ros2_context.outputs:context", "publish_front_3d_lidar_scan.inputs:context"),
("ros2_qos_profile.outputs:qosProfile", "publish_front_3d_lidar_scan.inputs:qosProfile"),
],
lidar_keys.SET_VALUES: [
("ros2_context.inputs:domain_id", 0),
("front_3d_lidar_render_product.inputs:cameraPrim", [Sdf.Path(LIDAR_PATH)]),
("front_3d_lidar_render_product.inputs:height", 720),
("front_3d_lidar_render_product.inputs:width", 1280),
("publish_front_3d_lidar_scan.inputs:frameId", "front_3d_lidar"),
("publish_front_3d_lidar_scan.inputs:topicName", "front_3d_lidar/lidar_points"),
("publish_front_3d_lidar_scan.inputs:type", "point_cloud"),
],
},
)
# Create a graph for subscribing to twist information (/cmd_vel).
ROS_TWIST_PATH = "/Nova_Carter_ROS/differential_drive"
CONTROLLER_PATH = "/Nova_Carter_ROS/chassis_link"
twist_keys = og.Controller.Keys
(ros_twist_graph, _, _, _) = og.Controller.edit(
{
"graph_path": ROS_TWIST_PATH,
"evaluator_name": "execution",
"pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
},
{
twist_keys.CREATE_NODES: [
("on_playback_tick", "omni.graph.action.OnPlaybackTick"),
("ros2_context", "isaacsim.ros2.bridge.ROS2Context"),
("ros2_subscribe_twist", "isaacsim.ros2.bridge.ROS2SubscribeTwist"),
("break_3_vector", "omni.graph.nodes.BreakVector3"),
("break_3_vector_01", "omni.graph.nodes.BreakVector3"),
("joint_wheel_left_name", "omni.graph.nodes.ConstantToken"),
("joint_wheel_right_name", "omni.graph.nodes.ConstantToken"),
("joint_name_array", "omni.graph.nodes.ConstructArray"),
# Even if arraySize is set to 2 in the Python code, input1 is not recognized; therefore, an array_insert_value node is created and passed via the controller.
("joint_name_array_add", "omni.graph.nodes.ArrayInsertValue"),
("differential_controller_01", "isaacsim.robot.wheeled_robots.DifferentialController"),
("articulation_controller_01", "isaacsim.core.nodes.IsaacArticulationController"),
],
twist_keys.SET_VALUES: [
("ros2_context.inputs:domain_id", 0),
("articulation_controller_01.inputs:targetPrim", [Sdf.Path(CONTROLLER_PATH)]),
("ros2_subscribe_twist.inputs:topicName", "cmd_vel"),
("joint_name_array.inputs:arrayType", "token[]"),
("joint_name_array.inputs:input0", "joint_wheel_left"),
# Even if arraySize is set to 2 in the Python code, input1 is not recognized; therefore, an array_insert_value node is created and passed via the controller.
("joint_name_array_add.inputs:index", 1),
("joint_name_array_add.inputs:value", "joint_wheel_right"),
("differential_controller_01.inputs:maxAcceleration", 2),
("differential_controller_01.inputs:maxAngularAcceleration", 2.68),
("differential_controller_01.inputs:maxAngularSpeed", 3),
("differential_controller_01.inputs:maxDeceleration", 2),
("differential_controller_01.inputs:maxLinearSpeed", 2),
("differential_controller_01.inputs:wheelDistance", 0.413),
("differential_controller_01.inputs:wheelRadius", 0.14),
],
twist_keys.CONNECT: [
("on_playback_tick.outputs:tick", "ros2_subscribe_twist.inputs:execIn"),
("on_playback_tick.outputs:tick", "differential_controller_01.inputs:execIn"),
("on_playback_tick.outputs:tick", "articulation_controller_01.inputs:execIn"),
("on_playback_tick.outputs:deltaSeconds", "differential_controller_01.inputs:dt"),
("ros2_context.outputs:context", "ros2_subscribe_twist.inputs:context"),
("ros2_subscribe_twist.outputs:linearVelocity", "break_3_vector_01.inputs:tuple"),
("ros2_subscribe_twist.outputs:angularVelocity", "break_3_vector.inputs:tuple"),
("break_3_vector_01.outputs:x", "differential_controller_01.inputs:linearVelocity"),
("break_3_vector.outputs:z", "differential_controller_01.inputs:angularVelocity"),
("differential_controller_01.outputs:velocityCommand", "articulation_controller_01.inputs:velocityCommand"),
("joint_name_array.outputs:array", "joint_name_array_add.inputs:array"),
# Even if arraySize is set to 2 in the Python code, input1 is not recognized; therefore, an array_insert_value node is created and passed via the controller.
("joint_name_array_add.outputs:array", "articulation_controller_01.inputs:jointNames"),
],
},
)
# TF TREE and odometry data publish graph creation.
TF_TREE_PATH = "/Nova_Carter_ROS/transform_tree_odometry"
BASE_LINK_PATH = "/Nova_Carter_ROS/chassis_link/base_link"
CHASSIS_LINK_PATH = "/Nova_Carter_ROS/chassis_link"
FRONT_LEFT_PATH = "/Nova_Carter_ROS/chassis_link/front_hawk/left"
WHEEL_LEFT_PATH = "/Nova_Carter_ROS/caster_wheel_left"
odom_keys = og.Controller.Keys
(ros_odom_graph, _, _, _) = og.Controller.edit(
{
"graph_path": TF_TREE_PATH,
"evaluator_name": "execution",
},
{
odom_keys.CREATE_NODES: [
("on_playback_tick", "omni.graph.action.OnPlaybackTick"),
("ros2_context", "isaacsim.ros2.bridge.ROS2Context"),
("ros2_qos_profile", "isaacsim.ros2.bridge.ROS2QoSProfile"),
("isaac_compute_odometry_node", "isaacsim.core.nodes.IsaacComputeOdometry"),
("ros2_publish_raw_transform_tree", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
("ros2_publish_odometry", "isaacsim.ros2.bridge.ROS2PublishOdometry"),
("isaac_read_simulation_time", "isaacsim.core.nodes.IsaacReadSimulationTime"),
("tf_tree_base_link_to_chassis", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("tf_tree_base_link_to_sensors", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("tf_tree_base_link_to_wheel_base", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
],
odom_keys.CONNECT: [
("on_playback_tick.outputs:tick", "isaac_compute_odometry_node.inputs:execIn"),
("on_playback_tick.outputs:tick", "ros2_publish_odometry.inputs:execIn"),
("on_playback_tick.outputs:tick", "ros2_publish_raw_transform_tree.inputs:execIn"),
("on_playback_tick.outputs:tick", "tf_tree_base_link_to_chassis.inputs:execIn"),
("on_playback_tick.outputs:tick", "tf_tree_base_link_to_sensors.inputs:execIn"),
("on_playback_tick.outputs:tick", "tf_tree_base_link_to_wheel_base.inputs:execIn"),
("isaac_compute_odometry_node.outputs:angularVelocity", "ros2_publish_odometry.inputs:angularVelocity"),
("isaac_compute_odometry_node.outputs:linearVelocity", "ros2_publish_odometry.inputs:linearVelocity"),
("isaac_compute_odometry_node.outputs:orientation", "ros2_publish_odometry.inputs:orientation"),
("isaac_compute_odometry_node.outputs:orientation", "ros2_publish_raw_transform_tree.inputs:rotation"),
("isaac_compute_odometry_node.outputs:position", "ros2_publish_odometry.inputs:position"),
("isaac_compute_odometry_node.outputs:position", "ros2_publish_raw_transform_tree.inputs:translation"),
("ros2_qos_profile.outputs:qosProfile", "ros2_publish_odometry.inputs:qosProfile"),
("ros2_qos_profile.outputs:qosProfile", "ros2_publish_raw_transform_tree.inputs:qosProfile"),
("ros2_qos_profile.outputs:qosProfile", "tf_tree_base_link_to_chassis.inputs:qosProfile"),
("ros2_qos_profile.outputs:qosProfile", "tf_tree_base_link_to_sensors.inputs:qosProfile"),
("ros2_qos_profile.outputs:qosProfile", "tf_tree_base_link_to_wheel_base.inputs:qosProfile"),
("isaac_read_simulation_time.outputs:simulationTime", "ros2_publish_odometry.inputs:timeStamp"),
("isaac_read_simulation_time.outputs:simulationTime", "ros2_publish_raw_transform_tree.inputs:timeStamp"),
("isaac_read_simulation_time.outputs:simulationTime", "tf_tree_base_link_to_chassis.inputs:timeStamp"),
("isaac_read_simulation_time.outputs:simulationTime", "tf_tree_base_link_to_sensors.inputs:timeStamp"),
("isaac_read_simulation_time.outputs:simulationTime", "tf_tree_base_link_to_wheel_base.inputs:timeStamp"),
("ros2_context.outputs:context", "ros2_publish_odometry.inputs:context"),
("ros2_context.outputs:context", "ros2_publish_raw_transform_tree.inputs:context"),
("ros2_context.outputs:context", "tf_tree_base_link_to_chassis.inputs:context"),
("ros2_context.outputs:context", "tf_tree_base_link_to_sensors.inputs:context"),
("ros2_context.outputs:context", "tf_tree_base_link_to_wheel_base.inputs:context"),
],
odom_keys.SET_VALUES: [
("ros2_context.inputs:domain_id", 0),
("isaac_compute_odometry_node.inputs:chassisPrim", [Sdf.Path(CHASSIS_LINK_PATH)]),
("ros2_publish_raw_transform_tree.inputs:childFrameId", "base_link"),
("ros2_publish_raw_transform_tree.inputs:parentFrameId", "odom"),
("ros2_publish_raw_transform_tree.inputs:topicName", "tf"),
("ros2_publish_odometry.inputs:chassisFrameId", "base_link"),
("ros2_publish_odometry.inputs:odomFrameId", "odom"),
("ros2_publish_odometry.inputs:topicName", "chassis/odom"),
("tf_tree_base_link_to_chassis.inputs:parentPrim", [Sdf.Path(BASE_LINK_PATH)]),
("tf_tree_base_link_to_chassis.inputs:targetPrims", [Sdf.Path(CHASSIS_LINK_PATH)]),
("tf_tree_base_link_to_chassis.inputs:topicName", "tf"),
("tf_tree_base_link_to_sensors.inputs:parentPrim", [Sdf.Path(BASE_LINK_PATH)]),
("tf_tree_base_link_to_sensors.inputs:targetPrims", [Sdf.Path(FRONT_LEFT_CAMERA_PATH)]),
("tf_tree_base_link_to_sensors.inputs:targetPrims", [Sdf.Path(LIDAR_PATH)]),
("tf_tree_base_link_to_sensors.inputs:targetPrims", [Sdf.Path(FRONT_HAWK_PATH)]),
("tf_tree_base_link_to_sensors.inputs:targetPrims", [Sdf.Path(FRONT_LEFT_PATH)]),
("tf_tree_base_link_to_sensors.inputs:topicName", "tf"),
("tf_tree_base_link_to_wheel_base.inputs:parentPrim", [Sdf.Path(CHASSIS_LINK_PATH)]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path(WHEEL_LEFT_PATH)]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path("/Nova_Carter_ROS/caster_wheel_right")]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path("/Nova_Carter_ROS/caster_swivel_right")]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path("/Nova_Carter_ROS/caster_swivel_left")]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path("/Nova_Carter_ROS/wheel_left")]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path("/Nova_Carter_ROS/wheel_right")]),
("tf_tree_base_link_to_wheel_base.inputs:targetPrims", [Sdf.Path("/Nova_Carter_ROS/caster_frame_base")]),
("tf_tree_base_link_to_wheel_base.inputs:topicName", "tf"),
],
},
)
simulation_app.update()
simulation_context = SimulationContext(physics_dt=1.0 / 60.0, rendering_dt=1.0 / 60.0, stage_units_in_meters=1.0)
simulation_context.play()
simulation_context.step(render=True)
async def run_graph_evaluation():
# await og.Controller.evaluate()
# Execute the ROS clock graph.
await og.Controller.evaluate(ros_clock_graph)
# Execute the ROS camera graph so that the configured ROS image publishers are activated within the SDG Pipeline.
await og.Controller.evaluate(front_hawk_graph)
# Execute the ROS LiDAR publish graph.
await og.Controller.evaluate(ros_lidar_graph)
# Execute the ROS Twist subscribe graph.
await og.Controller.evaluate(ros_twist_graph)
# Execute the ROS TF tree and odometry publish graph.
await og.Controller.evaluate(ros_odom_graph)
# Main simulation loop: Evaluate the other ROS graphs.
def main_simulation_loop():
frame = 0
ros_task_started = False
# Simulate for one second to warm up sim and let everything settle.
for frame in range(60):
simulation_context.step(render=True)
simulation_app.update()
while simulation_app.is_running():
simulation_app.update()
simulation_context.step(render=True)
frame += 1
asyncio.run(run_graph_evaluation())
# Execute the main simulation loop.
try:
main_simulation_loop()
except KeyboardInterrupt:
pass
finally:
simulation_context.stop()
simulation_app.close()
rclpy.shutdown()