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

Added laser data from map in nav2_loopback_sim #4617

Merged
merged 17 commits into from
Aug 20, 2024
Merged
Show file tree
Hide file tree
Changes from 7 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
186 changes: 169 additions & 17 deletions nav2_loopback_sim/nav2_loopback_sim/loopback_simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,23 @@
from geometry_msgs.msg import PoseWithCovarianceStamped, Twist
from geometry_msgs.msg import Quaternion, TransformStamped, Vector3
from nav_msgs.msg import Odometry
from nav_msgs.srv import GetMap
import rclpy
from rclpy.duration import Duration
from rclpy.node import Node
from rclpy.qos import DurabilityPolicy, QoSProfile, ReliabilityPolicy
from sensor_msgs.msg import LaserScan
from tf2_ros import TransformBroadcaster
from tf2_ros import Buffer, TransformBroadcaster, TransformListener
import tf_transformations

from .utils import addYawToQuat, matrixToTransform, transformStampedToMatrix

from .utils import (
addYawToQuat,
getMapOccupancy,
mapToWorld,
matrixToTransform,
transformStampedToMatrix,
worldToMap,
)

"""
This is a loopback simulator that replaces a physics simulator to create a
Expand All @@ -48,6 +55,7 @@ def __init__(self):
self.initial_pose = None
self.timer = None
self.setupTimer = None
self.map = None

self.declare_parameter('update_duration', 0.01)
self.update_dur = self.get_parameter('update_duration').get_parameter_value().double_value
Expand Down Expand Up @@ -88,6 +96,14 @@ def __init__(self):
self.scan_pub = self.create_publisher(LaserScan, 'scan', sensor_qos)

self.setupTimer = self.create_timer(0.1, self.setupTimerCallback)

self.map_client = self.create_client(GetMap, '/map_server/map')

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

self.getMap()
JatinPatil2003 marked this conversation as resolved.
Show resolved Hide resolved

self.info('Loopback simulator initialized')

def setupTimerCallback(self):
Expand Down Expand Up @@ -122,6 +138,7 @@ def initialPoseCallback(self, msg):
self.setupTimer.destroy()
self.setupTimer = None
self.timer = self.create_timer(self.update_dur, self.timerCallback)
self.timer_laser = self.create_timer(0.1, self.publishLaserScan)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
return

self.initial_pose = msg.pose.pose
Expand Down Expand Up @@ -165,23 +182,27 @@ def timerCallback(self):

self.publishTransforms(self.t_map_to_odom, self.t_odom_to_base_link)
self.publishOdometry(self.t_odom_to_base_link)
self.publishLaserScan()

def publishLaserScan(self):
# Publish a bogus laser scan for collision monitor
scan = LaserScan()
# scan.header.stamp = (self.get_clock().now()).to_msg()
scan.header.frame_id = self.scan_frame_id
scan.angle_min = -math.pi
scan.angle_max = math.pi
scan.angle_increment = 0.005817705996 # 0.333 degrees
scan.time_increment = 0.0
scan.scan_time = 0.1
scan.range_min = 0.1
scan.range_max = 100.0
num_samples = int((scan.angle_max - scan.angle_min) / scan.angle_increment)
scan.ranges = [scan.range_max - 0.01] * num_samples
self.scan_pub.publish(scan)
self.scan_msg = LaserScan()
# self.scan_msg.header.stamp = (self.get_clock().now()).to_msg()
JatinPatil2003 marked this conversation as resolved.
Show resolved Hide resolved
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
self.scan_msg.header.frame_id = self.scan_frame_id
self.scan_msg.angle_min = -math.pi
self.scan_msg.angle_max = math.pi
# 1.5 degrees
self.scan_msg.angle_increment = 0.0261799
self.scan_msg.time_increment = 0.0
self.scan_msg.scan_time = 0.1
self.scan_msg.range_min = 0.05
self.scan_msg.range_max = 100.0
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
num_samples = int(
(self.scan_msg.angle_max - self.scan_msg.angle_min) /
self.scan_msg.angle_increment)
self.scan_msg.ranges = [0.0] * num_samples
x, y, theta = self.getLaserPose()
self.getLaserScan(num_samples, x, y, theta)
self.scan_pub.publish(self.scan_msg)

def publishTransforms(self, map_to_odom, odom_to_base_link):
map_to_odom.header.stamp = \
Expand Down Expand Up @@ -209,6 +230,137 @@ def debug(self, msg):
self.get_logger().debug(msg)
return

def getMap(self):
request = GetMap.Request()
if self.map_client.wait_for_service(timeout_sec=5.0):
# Request to get map
future = self.map_client.call_async(request)
rclpy.spin_until_future_complete(self, future)
if future.result() is not None:
self.map = future.result().map
self.get_logger().info('Laser scan will be populated using map data')
else:
self.get_logger().warn(
'Failed to get map, '
'Laser scan will be populated using max range'
)
else:
self.get_logger().warn(
'Failed to get map, '
'Laser scan will be populated using max range'
)

def getLaserPose(self):
if self.initial_pose is None:
return 0.0, 0.0, 0.0

try:
# Wait for transform and lookup
now = rclpy.time.Time()
transform = self.tf_buffer.lookup_transform(
'map', self.scan_frame_id, now, rclpy.duration.Duration(seconds=0.1))

# Extract pose information
x = transform.transform.translation.x
y = transform.transform.translation.y
rotation = transform.transform.rotation
theta = tf_transformations.euler_from_quaternion([
rotation.x,
rotation.y,
rotation.z,
rotation.w
])[2]

return x, y, theta

except Exception as ex:
self.get_logger().error('Transform lookup failed: %s' % str(ex))
return 0.0, 0.0, 0.0

def getLaserScan(self, num_samples, x, y, theta):
if self.map is None or self.initial_pose is None:
self.scan_msg.ranges = [self.scan_msg.range_max - 0.1] * num_samples
return

mx, my = worldToMap(x, y, self.map)

if not mx and not my:
self.scan_msg.ranges = [self.scan_msg.range_max - 0.1] * num_samples
return

for i in range(int(num_samples)):
curr_angle = theta + self.scan_msg.angle_min + i * self.scan_msg.angle_increment
self.scan_msg.ranges[i] = self.findMapRange(mx, my, x, y, curr_angle)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

def findMapRange(self, mx, my, x, y, theta):
# Using "A Faster Voxel Traversal Algorithm for Ray Tracing" by Amanatides & Woo
# ======== Initialization Phase ========
origin = [x, y] # u
direction = [math.cos(theta), math.sin(theta)] # v

current = [mx, my] # X, Y
step = [0, 0] # stepX, stepY
tMax = [0.0, 0.0] # tMaxX, tMaxY
tDelta = [0.0, 0.0] # tDeltaX, tDeltaY

voxel_border = [0.0, 0.0]
voxel_border[0], voxel_border[1] = mapToWorld(
current[0], current[1], self.map)

for i in range(2): # For each dimension (x, y)
# Determine step direction
if direction[i] > 0.0:
step[i] = 1
elif direction[i] < 0.0:
step[i] = -1
else:
step[i] = 0

# Determine tMax, tDelta
if step[i] != 0:
if step[i] == 1:
voxel_border[i] += step[i] * self.map.info.resolution

# tMax - voxel boundary crossing
tMax[i] = (voxel_border[i] - origin[i]) / direction[i]
# tDelta - distance along ray
# so that vertical/horizontal component equals one voxel
tDelta[i] = self.map.info.resolution / abs(direction[i])
else:
tMax[i] = float('inf')
tDelta[i] = float('inf')

# ======== Incremental Traversal ========
while True:
# Advance
dim = 0 if tMax[0] < tMax[1] else 1

# Advance one voxel
current[dim] += step[dim]
tMax[dim] += tDelta[dim]

# Check map inbounds
if (current[0] < 0 or current[0] >= self.map.info.width or
current[1] < 0 or current[1] >= self.map.info.height):
return self.scan_msg.range_max - 0.1

# Determine current range
current_range = math.sqrt(
(current[0] - mx) ** 2 + (current[1] - my) ** 2
) * self.map.info.resolution

# Are we at max range?
if current_range > self.scan_msg.range_max:
return self.scan_msg.range_max - 0.1
else:
occ = getMapOccupancy(current[0], current[1], self.map)
if occ >= 60: # Current cell is occupied
# Is range less than min range
if current_range < self.scan_msg.range_min:
return 0.0

return current_range


def main():
rclpy.init()
Expand Down
25 changes: 25 additions & 0 deletions nav2_loopback_sim/nav2_loopback_sim/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
# limitations under the License.


import math

from geometry_msgs.msg import Quaternion, Transform
import numpy as np
import tf_transformations
Expand Down Expand Up @@ -63,3 +65,26 @@ def matrixToTransform(matrix):
transform.rotation.z = quaternion[2]
transform.rotation.w = quaternion[3]
return transform


def worldToMap(world_x, world_y, map_msg):
# Check if world coordinates are out of bounds
if (world_x < map_msg.info.origin.position.x or world_y < map_msg.info.origin.position.y):
return None, None # Coordinates are out of bounds

map_x = int(math.floor((world_x - map_msg.info.origin.position.x) / map_msg.info.resolution))
map_y = int(math.floor((world_y - map_msg.info.origin.position.y) / map_msg.info.resolution))

if not map_x < map_msg.info.width or not map_y < map_msg.info.height:
return None, None # Coordinates are out of bounds
return map_x, map_y


def mapToWorld(map_x, map_y, map_msg):
world_x = map_msg.info.origin.position.x + ((map_x + 0.5) * map_msg.info.resolution)
world_y = map_msg.info.origin.position.y + ((map_y + 0.5) * map_msg.info.resolution)
return world_x, world_y


def getMapOccupancy(x, y, map_msg):
return map_msg.data[y * map_msg.info.width + x]
Loading