Skip to content

Commit

Permalink
drop performance by half
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski committed Aug 9, 2024
1 parent 5f2c337 commit 4f12b72
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 5 deletions.
2 changes: 1 addition & 1 deletion nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -426,4 +426,4 @@ loopback_simulator:
odom_frame_id: "odom"
map_frame_id: "map"
scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link'
update_duration: 0.01
update_duration: 0.02
5 changes: 1 addition & 4 deletions nav2_loopback_sim/nav2_loopback_sim/loopback_simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,6 @@ def __init__(self):
self.t_odom_to_base_link.child_frame_id = self.base_frame_id

self.tf_broadcaster = TransformBroadcaster(self)
self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)

self.initial_pose_sub = self.create_subscription(
PoseWithCovarianceStamped,
Expand Down Expand Up @@ -180,8 +178,7 @@ def publishLaserScan(self):
scan.range_min = 0.1
scan.range_max = 100.0
num_samples = int((scan.angle_max - scan.angle_min) / scan.angle_increment)
for i in range(num_samples):
scan.ranges.append(scan.range_max - 0.01)
scan.ranges = [scan.range_max - 0.01] * num_samples
self.scan_pub.publish(scan)

def publishTransforms(self, map_to_odom, odom_to_base_link):
Expand Down

0 comments on commit 4f12b72

Please sign in to comment.