You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I have an Ouster OS1-32U 3D lidar and an Intel Realsense and they both combined make up to 35 publishers including the depth clouds from both the sensors and their respective IMU data. The incoming data is as I require viz IMU at 200Hz, OS cloud at 20, and Realsense Cloud at 30Hz. But when I start recording the bag file and play the recorded bag file my messages are not as per the frame rates I mentioned above and they are significantly less (almost 0 for a few seconds).
Previously I was using Cyclone DDS which I think is bottlenecking the data transport hence I want to shift to FastRTPS, but it seems I am unable to reproduce the same profile manner here i.e (Publish in unicast mode and only to the localhost and not any other connected PC, increase the incoming buffer size).
Steps to reproduce issue
Launch the Ouster lidar and realsense camera nodes, then launch the rosbag record node. Launch file
ouster_launch=IncludeLaunchDescription(
XMLLaunchDescriptionSource(
[
PathJoinSubstitution(
[FindPackageShare("ouster_ros"), "launch", "sensor.launch.xml"]
)
]
),
launch_arguments={
"viz": "false",
"sensor_hostname": "os-122212000733.local", # Replace with the actual sensor hostname"lidar_mode": "1024x20",
"udp_profile_lidar": "RNG19_RFL8_SIG16_NIR16",
"metadata": "/home/scout/autonomy-stack/src/os-122212000733-metadata.json", # Replace with relative path to metadata file"timestamp_mode": "TIME_FROM_ROS_TIME",
}.items(),
)
realsense_launch=IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
PathJoinSubstitution(
[FindPackageShare("realsense2_camera"), "launch", "rs_launch.py"]
)
]
),
launch_arguments={
"initial_reset": "true",
"pointcloud.enable": "true",
"enable_infra1": "false",
"enable_infra2": "false",
"enable_sync": "true",
"align_depth.enable": "true",
"enable_gyro": "true",
"enable_accel": "true",
"gyro_fps": "200",
"accel_fps": "200",
"unite_imu_method": "2",
}.items(),
)
# No compression of bag file, just splitting.rosbag_record=ExecuteProcess(
cmd=[
"ros2",
"bag",
"record",
"-o",
directory,
"--qos-profile-overrides-path",
Qos_override,
"--max-cache-size",
"1000000000", # 1 GB"--max-bag-size",
"3221225472", # 3Gb of raw data"--max-bag-duration",
"1800", # seconds"-s",
"sqlite3",
"-a",
],
shell=True,
)
i.e (Publish in unicast mode and only to the localhost and not any other connected PC, increase the incoming buffer size).
for localhost, ROS 2 provides ROS_LOCALHOST_ONLY environment variable to isolate the communication in the localhost. this is much easier and agnostic from rmw implementation.
besides that, why did you disable data sharing and shared memory transport? i think those are meant to be used for localhost low latency high throughput communication.
@fujitatomoya I tried using the ROS_LOCALHOST_ONLY but it didn't work in my case, a more detailed problem can be found here. Regarding data sharing and shared memory transport, I was looking into the config on how fastrtps performs with my sensor suite, and no specific reason for it.
Description
How to write Fast RTPS XML profile to publish in unicast mode with modified socket buffer sizes similar to the provided cycloneDDS profile.
Cyclone DDS
My not working Fast RTPS profile
Details
I have an Ouster OS1-32U 3D lidar and an Intel Realsense and they both combined make up to 35 publishers including the depth clouds from both the sensors and their respective IMU data. The incoming data is as I require viz IMU at 200Hz, OS cloud at 20, and Realsense Cloud at 30Hz. But when I start recording the bag file and play the recorded bag file my messages are not as per the frame rates I mentioned above and they are significantly less (almost 0 for a few seconds).
Previously I was using Cyclone DDS which I think is bottlenecking the data transport hence I want to shift to FastRTPS, but it seems I am unable to reproduce the same profile manner here i.e (Publish in unicast mode and only to the localhost and not any other connected PC, increase the incoming buffer size).
Steps to reproduce issue
Launch file
Expected behavior
Actual behavior
Thanks.
The text was updated successfully, but these errors were encountered: