Isaac Sim Version
5.0.0
Operating System
Ubuntu 22.04
GPU Information
- Model: NVIDIA RTX 3500 Ada Generation
- Driver Version: 580.95.05
Topic Description
TF trees are separated in RViz2 and inside Isaac Sim (using the TF extension), even though frames are connected, and I’ve separated static frames on /tf_static and dynamic frames on /tf.
Detailed Description
What we’re aiming for
A standard mobile robot TF chain:
world → map(static)map → odom(static or SLAM‑owned)odom → base_footprint(dynamic from odometry)base_footprint → base_link(static, slight offset)- downstream frames from
base_linkto wheels, sensors, arm joints (dynamic)
What the code currently does
- Fixed base – locobot_base_footprint
to/Worldvia aFixedJoint(to prevent drift). We also publishworld→mapandmap→odomas identity transforms on/tf_static, and publishodom→base_footprintas an identity transform via aROS2PublishRawTransformTree`. This means the robot’s chassis is effectively fixed: there is no dynamic odom→base_footprint transform. - Dynamic chain – TF frames from
locobot_base_linkto wheels, casters, sensors, the camera tower, and the arm chain are published each tick viaROS2PublishTransformTreenodes. Those downstream transforms rely on the articulation state of the robot (wheels turning, pan/tilt joints, arm joints). - Joint state publishing – A unified joint‑state graph publishes joint states and accepts commands via
/locobot/joint_statesand/locobot/joint_states_cmd. There is only one TF publisher for each link chain.
Observations
- Frames drift relative to base – Even with the base fixed, the
locobot_base_link,locobot_camera_tower_link, andlocobot_arm_base_linkframes visibly snap or creep over time. In some cases their axes jump far away (kilometres) in RViz2. - No duplicate odom→base_footprint – We deliberately disabled the dynamic odom→base_footprint broadcast; instead it’s a static identity. So this drift is not coming from two competing broadcasters for the base.
Screenshots or Videos
Additional Information
What I’ve Tried
- Verified that there is exactly one TF publisher for each transform: no duplicate odom→base_footprint.
- Ensured that all true static transforms (
world→map,map→odom,odom→base_footprint) are on/tf_staticwith Transient Local durability. - Confirmed the chassis is pinned via a
FixedJointto/World. - Verified that no SLAM or external node is publishing
map→odomorodom→base_footprint. - Tried wiring the TF publishers in different orders; no change.
- Checked joint‑state QoS settings and confirmed there is only one joint‑state publisher.
Code
#!/usr/bin/env python3
import time
import logging
import omni.graph.core as og
import carb
from typing import Dict, Optional
# Configure logging
logging.basicConfig(level=logging.INFO)
logger = logging.getLogger("ROS2ClockTF_USD")
class ROS2ClockTF_USD:
"""Manages ROS2 bridge functionality in Isaac Sim."""
def __init__(self, domain_id: int = 0):
"""Initialize the ROS2 bridge handler.
Args:
domain_id (int): ROS_DOMAIN_ID for communication (default: 0)
"""
self._domain_id = domain_id
self._graph_paths: Dict[str, str] = {}
self._initialized = False
try:
# Allow time for extensions to fully load
time.sleep(1.0)
self._initialized = True
logger.info("ROS2 bridge handler initialized successfully")
except Exception as e:
logger.error(f"Failed to initialize ROS2 bridge handler: {str(e)}")
raise
def setup_clock(self) -> bool:
"""Setup the ROS2 clock publisher.
Returns:
bool: True if setup successful
"""
try:
graph_path = "/World/ROSClock"
keys = og.Controller.Keys
(graph, _, _, _) = og.Controller.edit(
{"graph_path": graph_path, "evaluator_name": "execution"},
{
keys.CREATE_NODES: [
("Context", "isaacsim.ros2.bridge.ROS2Context"),
("OnTick", "omni.graph.action.OnPlaybackTick"),
("ReadSimTime", "isaacsim.core.nodes.IsaacReadSimulationTime"),
("PublishClock", "isaacsim.ros2.bridge.ROS2PublishClock")
],
keys.CONNECT: [
("OnTick.outputs:tick", "PublishClock.inputs:execIn"),
("ReadSimTime.outputs:simulationTime", "PublishClock.inputs:timeStamp"),
("Context.outputs:context", "PublishClock.inputs:context")
],
keys.SET_VALUES: [
("Context.inputs:domain_id", self._domain_id)
]
}
)
self._graph_paths["clock"] = graph_path
logger.info("Successfully setup ROS2 clock")
return True
except Exception as e:
logger.error(f"Failed to setup ROS2 clock: {str(e)}")
return False
def setup_joint_state_publisher(self, robot_prim_path: str = "/World/locobot") -> bool:
"""DEPRECATED: Joint state system is now handled by unified system in locobot_components_loading.py
This method is kept for backward compatibility but does nothing.
"""
logger.info("Joint state publisher setup skipped - using unified system from locobot_components_loading.py")
return True
def setup_transform_tree(self, robot_prim_path: str = "/World/locobot") -> bool:
try:
# Joint state system is now handled by the unified system in locobot_components_loading.py
logger.info("Joint state system handled separately by unified system")
# Define graph path
graph_path = f"{robot_prim_path}/tfTrees"
keys = og.Controller.Keys
publish_map_frames = True
create_nodes = [
("OnTick", "omni.graph.action.OnPlaybackTick"),
("ReadSimTime", "isaacsim.core.nodes.IsaacReadSimulationTime"),
("Context", "isaacsim.ros2.bridge.ROS2Context"),
("PublishOdom", "isaacsim.ros2.bridge.ROS2PublishOdometry"),
("ComputeOdom", "isaacsim.core.nodes.IsaacComputeOdometry"),
("PublishOdomToFootprintTF", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
("PublishFootprintToBaseTF", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
("PublishBaseToWheelsTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishBaseToCastersTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishBaseToSensorsTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishBaseToPlateTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishPlateToBatteryTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishBaseToTowerTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishPlateToArmBaseTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishArmBaseToShoulderTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishShoulderToUpperArmTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishUpperArmToUpperForearmTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishUpperForearmToLowerForearmTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishLowerForearmToWristTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishWristToGripperTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishGripperToEEArmTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishEEArmToGripperPropTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishEEArmToGripperBarTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishGripperBarToFingersTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishFingersToLeftFingerTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishFingersToRightFingerTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishFingersToEEGripperTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishEEArmToARTagTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishTowerToPanTF", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
("PublishPanToTiltTF", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
("PublishTiltToCameraTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishCameraToDepthTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishTowerToLidarTowerTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishLidarTowerToLaserTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
("PublishBaseToIMULinkTF", "isaacsim.ros2.bridge.ROS2PublishTransformTree"),
]
if publish_map_frames:
create_nodes.extend([
("PublishWorldToMapTF", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
("PublishMapToOdomTF", "isaacsim.ros2.bridge.ROS2PublishRawTransformTree"),
])
connections = [
("OnTick.outputs:tick", "ComputeOdom.inputs:execIn"),
("OnTick.outputs:tick", "PublishOdomToFootprintTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishFootprintToBaseTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishBaseToWheelsTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishBaseToCastersTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishBaseToSensorsTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishBaseToPlateTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishPlateToBatteryTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishBaseToTowerTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishPlateToArmBaseTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishArmBaseToShoulderTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishShoulderToUpperArmTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishUpperArmToUpperForearmTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishUpperForearmToLowerForearmTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishLowerForearmToWristTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishWristToGripperTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishGripperToEEArmTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishEEArmToGripperPropTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishEEArmToGripperBarTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishGripperBarToFingersTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishFingersToLeftFingerTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishFingersToRightFingerTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishFingersToEEGripperTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishEEArmToARTagTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishTowerToPanTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishPanToTiltTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishTiltToCameraTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishCameraToDepthTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishTowerToLidarTowerTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishLidarTowerToLaserTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishBaseToIMULinkTF.inputs:execIn"),
("ReadSimTime.outputs:simulationTime", "PublishOdom.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishOdomToFootprintTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishFootprintToBaseTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishBaseToWheelsTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishBaseToCastersTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishBaseToSensorsTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishBaseToPlateTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishPlateToBatteryTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishBaseToTowerTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishPlateToArmBaseTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishArmBaseToShoulderTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishShoulderToUpperArmTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishUpperArmToUpperForearmTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishUpperForearmToLowerForearmTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishLowerForearmToWristTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishWristToGripperTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishGripperToEEArmTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishEEArmToGripperPropTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishEEArmToGripperBarTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishGripperBarToFingersTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishFingersToLeftFingerTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishFingersToRightFingerTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishFingersToEEGripperTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishEEArmToARTagTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishTowerToPanTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishPanToTiltTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishTiltToCameraTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishCameraToDepthTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishTowerToLidarTowerTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishLidarTowerToLaserTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishBaseToIMULinkTF.inputs:timeStamp"),
("Context.outputs:context", "PublishOdom.inputs:context"),
("Context.outputs:context", "PublishOdomToFootprintTF.inputs:context"),
("Context.outputs:context", "PublishFootprintToBaseTF.inputs:context"),
("ComputeOdom.outputs:execOut", "PublishOdom.inputs:execIn"),
("ComputeOdom.outputs:angularVelocity", "PublishOdom.inputs:angularVelocity"),
("ComputeOdom.outputs:linearVelocity", "PublishOdom.inputs:linearVelocity"),
("ComputeOdom.outputs:position", "PublishOdom.inputs:position"),
("ComputeOdom.outputs:orientation", "PublishOdom.inputs:orientation"),
("ComputeOdom.outputs:position", "PublishOdomToFootprintTF.inputs:translation"),
("ComputeOdom.outputs:orientation", "PublishOdomToFootprintTF.inputs:rotation"),
("Context.outputs:context", "PublishBaseToWheelsTF.inputs:context"),
("Context.outputs:context", "PublishBaseToCastersTF.inputs:context"),
("Context.outputs:context", "PublishBaseToSensorsTF.inputs:context"),
("Context.outputs:context", "PublishBaseToPlateTF.inputs:context"),
("Context.outputs:context", "PublishPlateToBatteryTF.inputs:context"),
("Context.outputs:context", "PublishBaseToTowerTF.inputs:context"),
("Context.outputs:context", "PublishPlateToArmBaseTF.inputs:context"),
("Context.outputs:context", "PublishArmBaseToShoulderTF.inputs:context"),
("Context.outputs:context", "PublishShoulderToUpperArmTF.inputs:context"),
("Context.outputs:context", "PublishUpperArmToUpperForearmTF.inputs:context"),
("Context.outputs:context", "PublishUpperForearmToLowerForearmTF.inputs:context"),
("Context.outputs:context", "PublishLowerForearmToWristTF.inputs:context"),
("Context.outputs:context", "PublishWristToGripperTF.inputs:context"),
("Context.outputs:context", "PublishGripperToEEArmTF.inputs:context"),
("Context.outputs:context", "PublishEEArmToGripperPropTF.inputs:context"),
("Context.outputs:context", "PublishEEArmToGripperBarTF.inputs:context"),
("Context.outputs:context", "PublishGripperBarToFingersTF.inputs:context"),
("Context.outputs:context", "PublishFingersToLeftFingerTF.inputs:context"),
("Context.outputs:context", "PublishFingersToRightFingerTF.inputs:context"),
("Context.outputs:context", "PublishFingersToEEGripperTF.inputs:context"),
("Context.outputs:context", "PublishEEArmToARTagTF.inputs:context"),
("Context.outputs:context", "PublishTowerToPanTF.inputs:context"),
("Context.outputs:context", "PublishPanToTiltTF.inputs:context"),
("Context.outputs:context", "PublishTiltToCameraTF.inputs:context"),
("Context.outputs:context", "PublishCameraToDepthTF.inputs:context"),
("Context.outputs:context", "PublishTowerToLidarTowerTF.inputs:context"),
("Context.outputs:context", "PublishLidarTowerToLaserTF.inputs:context"),
("Context.outputs:context", "PublishBaseToIMULinkTF.inputs:context"),
]
if publish_map_frames:
connections.extend([
("OnTick.outputs:tick", "PublishWorldToMapTF.inputs:execIn"),
("OnTick.outputs:tick", "PublishMapToOdomTF.inputs:execIn"),
("ReadSimTime.outputs:simulationTime", "PublishWorldToMapTF.inputs:timeStamp"),
("ReadSimTime.outputs:simulationTime", "PublishMapToOdomTF.inputs:timeStamp"),
("Context.outputs:context", "PublishWorldToMapTF.inputs:context"),
("Context.outputs:context", "PublishMapToOdomTF.inputs:context"),
])
set_values = [
("Context.inputs:domain_id", self._domain_id),
("ComputeOdom.inputs:chassisPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishOdom.inputs:topicName", "odom"),
("PublishOdom.inputs:odomFrameId", "odom"),
("PublishOdom.inputs:chassisFrameId", "locobot_base_footprint"),
("PublishOdomToFootprintTF.inputs:topicName", "tf"),
("PublishOdomToFootprintTF.inputs:parentFrameId", "odom"),
("PublishOdomToFootprintTF.inputs:childFrameId", "locobot_base_footprint"),
("PublishFootprintToBaseTF.inputs:topicName", "tf"),
("PublishFootprintToBaseTF.inputs:parentFrameId", "locobot_base_footprint"),
("PublishFootprintToBaseTF.inputs:childFrameId", "locobot_base_link"),
("PublishFootprintToBaseTF.inputs:translation", [0.0, 0.0, 0.0]),
("PublishFootprintToBaseTF.inputs:rotation", [0.0, 0.0, 0.0, 1.0]),
# base_link -> wheels (ACTUAL Isaac Sim structure - wheels at robot root)
("PublishBaseToWheelsTF.inputs:topicName", "tf"),
("PublishBaseToWheelsTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishBaseToWheelsTF.inputs:targetPrims", [
f"{robot_prim_path}/locobot_wheel_left_link",
f"{robot_prim_path}/locobot_wheel_right_link",
]),
# base_link -> casters
("PublishBaseToCastersTF.inputs:topicName", "tf"),
("PublishBaseToCastersTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishBaseToCastersTF.inputs:targetPrims", [
f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_caster_front_link",
f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_caster_back_link",
]),
# base_link -> sensors
("PublishBaseToSensorsTF.inputs:topicName", "tf"),
("PublishBaseToSensorsTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishBaseToSensorsTF.inputs:targetPrims", [
f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_gyro_link",
f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_cliff_sensor_left_link",
f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_cliff_sensor_right_link",
f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_cliff_sensor_front_link",
]),
# base_link -> plate
("PublishBaseToPlateTF.inputs:topicName", "tf"),
("PublishBaseToPlateTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishBaseToPlateTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_plate_link"]),
# plate -> battery
("PublishPlateToBatteryTF.inputs:topicName", "tf"),
("PublishPlateToBatteryTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_plate_link"),
("PublishPlateToBatteryTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_plate_link/locobot_battery_link"]),
# base_link -> camera_tower
("PublishBaseToTowerTF.inputs:topicName", "tf"),
("PublishBaseToTowerTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishBaseToTowerTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_camera_tower_link"]),
# plate -> arm_base
("PublishPlateToArmBaseTF.inputs:topicName", "tf"),
("PublishPlateToArmBaseTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_plate_link"),
("PublishPlateToArmBaseTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_plate_link/locobot_arm_base_link"]),
# Arm kinematic chain (ACTUAL Isaac Sim structure - all at robot root)
# arm_base -> shoulder
("PublishArmBaseToShoulderTF.inputs:topicName", "tf"),
("PublishArmBaseToShoulderTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_plate_link/locobot_arm_base_link"),
("PublishArmBaseToShoulderTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_shoulder_link"]),
# shoulder -> upper_arm
("PublishShoulderToUpperArmTF.inputs:topicName", "tf"),
("PublishShoulderToUpperArmTF.inputs:parentPrim", f"{robot_prim_path}/locobot_shoulder_link"),
("PublishShoulderToUpperArmTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_upper_arm_link"]),
# upper_arm -> upper_forearm
("PublishUpperArmToUpperForearmTF.inputs:topicName", "tf"),
("PublishUpperArmToUpperForearmTF.inputs:parentPrim", f"{robot_prim_path}/locobot_upper_arm_link"),
("PublishUpperArmToUpperForearmTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_upper_forearm_link"]),
# upper_forearm -> lower_forearm
("PublishUpperForearmToLowerForearmTF.inputs:topicName", "tf"),
("PublishUpperForearmToLowerForearmTF.inputs:parentPrim", f"{robot_prim_path}/locobot_upper_forearm_link"),
("PublishUpperForearmToLowerForearmTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_lower_forearm_link"]),
# lower_forearm -> wrist
("PublishLowerForearmToWristTF.inputs:topicName", "tf"),
("PublishLowerForearmToWristTF.inputs:parentPrim", f"{robot_prim_path}/locobot_lower_forearm_link"),
("PublishLowerForearmToWristTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_wrist_link"]),
# wrist -> gripper
("PublishWristToGripperTF.inputs:topicName", "tf"),
("PublishWristToGripperTF.inputs:parentPrim", f"{robot_prim_path}/locobot_wrist_link"),
("PublishWristToGripperTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_link"]),
# gripper -> ee_arm (ACTUAL: gripper at root, ee_arm nested under it)
("PublishGripperToEEArmTF.inputs:topicName", "tf"),
("PublishGripperToEEArmTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link"),
("PublishGripperToEEArmTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link"]),
# ee_arm -> gripper_prop (ACTUAL: gripper_prop at root level)
("PublishEEArmToGripperPropTF.inputs:topicName", "tf"),
("PublishEEArmToGripperPropTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link"),
("PublishEEArmToGripperPropTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_prop_link"]),
# ee_arm -> gripper_bar (ACTUAL: nested under gripper/ee_arm)
("PublishEEArmToGripperBarTF.inputs:topicName", "tf"),
("PublishEEArmToGripperBarTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link"),
("PublishEEArmToGripperBarTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link"]),
# gripper_bar -> fingers (ACTUAL: nested)
("PublishGripperBarToFingersTF.inputs:topicName", "tf"),
("PublishGripperBarToFingersTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link"),
("PublishGripperBarToFingersTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link/locobot_fingers_link"]),
# fingers -> left_finger (ACTUAL: left/right at root level)
("PublishFingersToLeftFingerTF.inputs:topicName", "tf"),
("PublishFingersToLeftFingerTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link/locobot_fingers_link"),
("PublishFingersToLeftFingerTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_left_finger_link"]),
# fingers -> right_finger (ACTUAL: at root level)
("PublishFingersToRightFingerTF.inputs:topicName", "tf"),
("PublishFingersToRightFingerTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link/locobot_fingers_link"),
("PublishFingersToRightFingerTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_right_finger_link"]),
# fingers -> ee_gripper (ACTUAL: nested under fingers)
("PublishFingersToEEGripperTF.inputs:topicName", "tf"),
("PublishFingersToEEGripperTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link/locobot_fingers_link"),
("PublishFingersToEEGripperTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_gripper_bar_link/locobot_fingers_link/locobot_ee_gripper_link"]),
# ee_arm -> ar_tag (ACTUAL: nested under ee_arm)
("PublishEEArmToARTagTF.inputs:topicName", "tf"),
("PublishEEArmToARTagTF.inputs:parentPrim", f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link"),
("PublishEEArmToARTagTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_gripper_link/locobot_ee_arm_link/locobot_ar_tag_link"]),
# Camera tower chain (ACTUAL: pan/tilt at root, camera nested under tilt)
# camera_tower -> pan (FIXED: pan at root level, use explicit transform from URDF)
("PublishTowerToPanTF.inputs:topicName", "tf"),
("PublishTowerToPanTF.inputs:parentFrameId", "locobot_camera_tower_link"),
("PublishTowerToPanTF.inputs:childFrameId", "locobot_pan_link"),
("PublishTowerToPanTF.inputs:translation", [0.047228, 0.0, 0.44425]),
("PublishTowerToPanTF.inputs:rotation", [0.0, 0.0, 0.0, 1.0]),
# pan -> tilt (FIXED: tilt at root level, use explicit transform from URDF)
("PublishPanToTiltTF.inputs:topicName", "tf"),
("PublishPanToTiltTF.inputs:parentFrameId", "locobot_pan_link"),
("PublishPanToTiltTF.inputs:childFrameId", "locobot_tilt_link"),
("PublishPanToTiltTF.inputs:translation", [0.025034, 0.0, 0.019]),
("PublishPanToTiltTF.inputs:rotation", [0.0, 0.0, 0.0, 1.0]),
# tilt -> camera (ACTUAL: camera nested under tilt at root)
("PublishTiltToCameraTF.inputs:topicName", "tf"),
("PublishTiltToCameraTF.inputs:parentPrim", f"{robot_prim_path}/locobot_tilt_link"),
("PublishTiltToCameraTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_tilt_link/camera_locobot_link"]),
# camera -> depth (ACTUAL: depth nested under camera)
("PublishCameraToDepthTF.inputs:topicName", "tf"),
("PublishCameraToDepthTF.inputs:parentPrim", f"{robot_prim_path}/locobot_tilt_link/camera_locobot_link"),
("PublishCameraToDepthTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_tilt_link/camera_locobot_link/locobot_camera_depth_link"]),
# Lidar chain
# camera_tower -> lidar_tower
("PublishTowerToLidarTowerTF.inputs:topicName", "tf"),
("PublishTowerToLidarTowerTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_camera_tower_link"),
("PublishTowerToLidarTowerTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_camera_tower_link/locobot_lidar_tower_link"]),
# lidar_tower -> laser_frame
("PublishLidarTowerToLaserTF.inputs:topicName", "tf"),
("PublishLidarTowerToLaserTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_camera_tower_link/locobot_lidar_tower_link"),
("PublishLidarTowerToLaserTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_camera_tower_link/locobot_lidar_tower_link/locobot_laser_frame_link"]),
# base_link -> imu_link
("PublishBaseToIMULinkTF.inputs:topicName", "tf"),
("PublishBaseToIMULinkTF.inputs:parentPrim", f"{robot_prim_path}/locobot_base_footprint/locobot_base_link"),
("PublishBaseToIMULinkTF.inputs:targetPrims", [f"{robot_prim_path}/locobot_base_footprint/locobot_base_link/locobot_imu_link"]),
]
if publish_map_frames:
set_values.extend([
("PublishWorldToMapTF.inputs:topicName", "tf_static"),
("PublishWorldToMapTF.inputs:parentFrameId", "world"),
("PublishWorldToMapTF.inputs:childFrameId", "map"),
("PublishWorldToMapTF.inputs:staticPublisher", True),
("PublishWorldToMapTF.inputs:translation", [0.0, 0.0, 0.0]),
("PublishWorldToMapTF.inputs:rotation", [0.0, 0.0, 0.0, 1.0]),
("PublishMapToOdomTF.inputs:topicName", "tf_static"),
("PublishMapToOdomTF.inputs:parentFrameId", "map"),
("PublishMapToOdomTF.inputs:childFrameId", "odom"),
("PublishMapToOdomTF.inputs:translation", [0.0, 0.0, 0.0]),
("PublishMapToOdomTF.inputs:rotation", [0.0, 0.0, 0.0, 1.0]),
("PublishMapToOdomTF.inputs:staticPublisher", True),
])
(graph, _, _, _) = og.Controller.edit(
{"graph_path": graph_path, "evaluator_name": "execution"},
{
keys.CREATE_NODES: create_nodes,
keys.CONNECT: connections,
keys.SET_VALUES: set_values,
}
)
self._graph_paths["tf_tree"] = graph_path
logger.info("Successfully setup TF tree publishing")
return True
except Exception as e:
logger.error(f"Failed to setup TF tree: {str(e)}")
return False
def cleanup(self) -> None:
"""Clean up all created graphs."""
try:
for graph_name, graph_path in self._graph_paths.items():
og.Controller.edit({"graph_path": graph_path}, {"_DELETE": []})
logger.info(f"Deleted graph: {graph_name} at {graph_path}")
except Exception as e:
logger.error(f"Failed to clean up graphs: {str(e)}")
