SLAM

slam.py

Overview

slam.py is a minimal SLAM façade that publishes a blank occupancy map and identity odometry so that navigation stacks (e.g. move_base, rviz) can start before a real SLAM backend is available. It defines exactly which message types and frames future SLAM solutions must honour.

Interfaces (strongly-typed, stateless)

Direction / Type

Topic

Semantics

Required (sub)

/{robot}/fused_scan

sensor_msgs/LaserScan – pre-filtered scan from sensor_fusion

Required (sub)

/{robot}/odom_proc

nav_msgs/Odometry – upstream pose estimate (ignored by stub)

Provided (pub, latched)

/{robot}/map

nav_msgs/OccupancyGrid – blank grid, 0.05 m cells, all free/unknown

Provided (pub, latched)

/{robot}/odom_slam

nav_msgs/Odometry – identity pose, zero twist, frame_id odom

Coordinate frames

map ←— identity —→ odom ←— real TF —→ base_link No TF broadcaster here; downstream must supply static or real transforms.

Contract

Pre-conditions

  • Nodes publish /fused_scan at ≥ 1 Hz.

  • /odom_proc provides any Odometry messages (not used by stub).

Post-conditions

  • On the first incoming scan or odom message each publisher latches and makes the blank map and identity odom available.

  • No further updates unless subscribers re-connect.

Implementation notes

  • Map: 10 × 10 cells, 0.05 m resolution, origin (–2.5, –2.5) so (0,0) is map centre.

  • Odometry: pose = (0,0,0), orientation = unit quaternion, twist = zero.

  • Replace update_map and update_pose stubs to integrate real SLAM algorithms.

class slam.SLAM[source]

Bases: object

Stub container wiring subscribers and latched publishers.

Variables

map_pubrospy.Publisher

Latched publisher for the occupancy grid.

odom_pubrospy.Publisher

Latched publisher for identity odometry.

velnav_msgs.msg.Odometry

Last Odometry received from /odom_proc (not used by stub).

Initialise the SLAM stub node:

  1. Read robot_number from CLI.

  2. Initialise ROS node <robot>_slam_node.

  3. Subscribe to /fused_scan and /odom_proc.

  4. Advertise /map and /odom_slam with latch=True, queue_size=1.

callback(scan_msg: sensor_msgs.msg.LaserScan) None[source]

Handle incoming fused scan from /fused_scan.

Parameters:

scan_msg (sensor_msgs.msg.LaserScan) – Pre-filtered scan (ignored by stub).

callback_odom(data: nav_msgs.msg.Odometry) None[source]

Handle incoming odometry from /odom_proc.

Parameters:

data (nav_msgs.msg.Odometry) – Upstream odometry (ignored; stored for possible future use).