Skip to content

Commit

Permalink
set QoSProfile to BEST_EFFORT to fix ROBOTIS-GIT/turtlebot3_simulatio…
Browse files Browse the repository at this point in the history
  • Loading branch information
abhishek47kashyap committed May 18, 2023
1 parent db1a8a1 commit 927cbe4
Showing 1 changed file with 3 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

import rclpy
from rclpy.node import Node
from rclpy.qos import ReliabilityPolicy, QoSProfile
import numpy as np
from copy import deepcopy
import itertools
Expand Down Expand Up @@ -123,7 +124,8 @@ def __init__(self):
self.obstacles_circles = [] # list of obstacles represented as circles

# Subscribe to /scan topic on which input lidar data is available
self.create_subscription(LaserScan, 'scan', self.callback_lidar_data, 10)
self.create_subscription(LaserScan, 'scan', self.callback_lidar_data,
QoSProfile(depth=10, reliability=ReliabilityPolicy.BEST_EFFORT))

# Publish to detector ('detection' topic has subscriber in kf_hungarian_tracker)
self.detection_pub = self.create_publisher(ObstacleArray, 'detection', 10)
Expand Down

0 comments on commit 927cbe4

Please sign in to comment.