Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS topic issues (syncing/hz) #19

Open
delenius opened this issue Jul 8, 2024 · 6 comments
Open

ROS topic issues (syncing/hz) #19

delenius opened this issue Jul 8, 2024 · 6 comments

Comments

@delenius
Copy link

delenius commented Jul 8, 2024

  1. The command ros2 topic hz /robot0/front_cam/rgb does not return any info (even though I am getting images through it).
    All the other topics report some data.

  2. I am not able to sync the /robot0/front_cam/rgb and /robot0/point_cloud2 topics using message_filters.ApproximateTimeSynchronizer (or plain TimeSynchronizer). I can sync all the other topics. Any idea why?

  3. /robot0/point_cloud2 has timestamps of 0 for all messages, like this:

header:
  stamp:
    sec: 0
    nanosec: 0

(perhaps this is why no hz can be computed).

Note: I am using RMW_IMPLEMENTATION=rmw_cyclonedds_cpp as it solved some issues I had (the default dds did not work across different user accounts).

@abizovnuralem
Copy link
Owner

abizovnuralem commented Aug 14, 2024

What Wifi version are you using? Do you ping it while using the dog? What is the average delay in your network? (in ms)

@richard98hess444
Copy link
Contributor

Hi @delenius , I was also facing the same problem, and here's how I fixed it.

Some general information:

  • Ubuntu 22.04
  • ROS2 Humble
  • Isaac Sim 4.1.0
  • Situation: running ./run_sim.sh with --robot_amount 1 under the root of go2_omniverse. While echoing the /robot0/point_cloud2 topic, stamp is always 0.

The reason is that ROS_Clock is not set in ./run_sim.sh file, or more precisely, not in the omniverse_sim.py file if we dig into the run_sim.sh file. This webpage from Omniverse shows how to add a ROS_Clock in it. So here are some steps that we have to do.

First, open omnigraph.py in your go2_omniverse workspace and add the following code right under the create_front_cam_omnigraph function. Note that there are some small modifications comparing to omniverse webpage.

def create_ros2_clock():
    graph_path = f"/ROS_Clock"
    og.Controller.edit(
        {"graph_path": graph_path, 
         "evaluator_name": "execution",
         "pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_SIMULATION,},
        {
            og.Controller.Keys.CREATE_NODES: [
                ("ReadSimTime", "omni.isaac.core_nodes.IsaacReadSimulationTime"),
                ("Context", "omni.isaac.ros2_bridge.ROS2Context"),
                ("PublishClock", "omni.isaac.ros2_bridge.ROS2PublishClock"),
                ("OnPlaybackTick", "omni.graph.action.OnPlaybackTick"),
            ],
            og.Controller.Keys.CONNECT: [
                ("OnPlaybackTick.outputs:tick", "PublishClock.inputs:execIn"),
                ("ReadSimTime.outputs:simulationTime", "PublishClock.inputs:timeStamp"),
                ("Context.outputs:context", "PublishClock.inputs:context"),
            ],
            og.Controller.Keys.SET_VALUES: [
                ("PublishClock.inputs:topicName", "/clock"),
                ("Context.inputs:domain_id", 1),
            ],
        },
    )

Second, go back to omniverse_sim.py. Find the line that writes from omnigraph import create_front_cam_omnigraph. Import our create_ros2_clock, namely:

from omnigraph import create_front_cam_omnigraph, create_ros2_clock

and add create_ros2_clock() under create_front_cam_omnigraph(i) in the run_sim function.
If we run ./run_sim.sh now, the ROS_Clock action graph can be seen at the stage, which is at the top left of the Isaac Sim window. A /clock topic also appears if you run topic list. However, if you run ros2 topic echo /robot0/point_cloud2, the time stamp is still 0. This is due to RobotBaseNode.

Third, open ros2.py in go2_omniverse workspace and find the RobotBaseNode class. Go to publish_lidar and we see that no time stamp is written (while stamp is defined in imu and odom). Simple add the code

point_cloud.header.stamp = self.get_clock().now().to_msg()

under point_cloud.header = Header(frame_id="odom"). Now the Isaac Sim should publish all the sensor data with time stamp. Hope it works to you!

@abizovnuralem
Copy link
Owner

Hello @richard98hess444 ! Thanks for your contribution! Could you let me know how you ran this repo on 4.1? In my case, I face freezing and time in simulation is very slow.

@richard98hess444
Copy link
Contributor

Hi @abizovnuralem !
Besides the pre-requirements, I simply followed your instructions and everything was fine. I commanded out some lines like parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") and setup_custom_env() in omniverse_sim.py whenever I met build errors. Isaac Sim is slow especially I load my own map, but still acceptable. It works on my two laptops with RTX3070 and 2060, both using Isaac Sim 4.1.0.

@abizovnuralem
Copy link
Owner

abizovnuralem commented Aug 30, 2024

He @richard98hess444 ! Currently, this repo only supports 4.0 version, if you use 4.1 it will be laggy and slow. This is a known issue with 4.1, your laptop is powerful enough to do real-time. refer to #26 #30

@abizovnuralem
Copy link
Owner

Just updated the repo and fixed the speed issue.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants