diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/config/costmap_common_params.yaml b/jetson/ros2_ws/src/saltybot_nav2_slam/config/costmap_common_params.yaml
new file mode 100644
index 0000000..2b76a0b
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/config/costmap_common_params.yaml
@@ -0,0 +1,47 @@
+costmap_common_params:
+ update_frequency: 10.0
+ publish_frequency: 5.0
+ global_frame: map
+ robot_base_frame: base_link
+ use_sim_time: false
+ rolling_window: false
+ robot_radius: 0.35
+ plugins:
+ - name: static_layer
+ type: nav2_costmap_2d::StaticLayer
+ map_subscribe_transient_local: true
+ enabled: true
+ - name: obstacle_layer
+ type: nav2_costmap_2d::ObstacleLayer
+ enabled: true
+ observation_sources: scan camera_depth
+ scan:
+ topic: /scan
+ max_obstacle_height: 2.5
+ min_obstacle_height: 0.0
+ clearing: true
+ marking: true
+ data_type: LaserScan
+ camera_depth:
+ topic: /camera/depth/color/points
+ max_obstacle_height: 2.5
+ min_obstacle_height: 0.0
+ clearing: false
+ marking: true
+ data_type: PointCloud2
+ sensor_frame: camera_link
+ expected_update_rate: 15.0
+ observation_persistence: 0.0
+ inf_is_valid: false
+ filter: passthrough
+ filter_value: 5.0
+ - name: inflation_layer
+ type: nav2_costmap_2d::InflationLayer
+ enabled: true
+ inflation_radius: 0.55
+ cost_scaling_factor: 10.0
+ inflate_unknown: false
+ inflate_around_unknown: true
+ lethal_cost_threshold: 100
+ unknown_cost_value: -1
+ resolution: 0.05
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/config/dwb_local_planner_params.yaml b/jetson/ros2_ws/src/saltybot_nav2_slam/config/dwb_local_planner_params.yaml
new file mode 100644
index 0000000..fafda9f
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/config/dwb_local_planner_params.yaml
@@ -0,0 +1,59 @@
+dwb_local_planner:
+ ros__parameters:
+ max_vel_x: 5.5
+ min_vel_x: 0.0
+ max_vel_y: 0.0
+ min_vel_y: 0.0
+ max_vel_theta: 3.0
+ min_vel_theta: -3.0
+ acc_lim_x: 2.5
+ acc_lim_y: 0.0
+ acc_lim_theta: 2.5
+ decel_lim_x: -2.5
+ decel_lim_y: 0.0
+ decel_lim_theta: -2.5
+ vx_samples: 20
+ vy_samples: 1
+ vtheta_samples: 40
+ sim_time: 1.7
+ sim_granularity: 0.05
+ angular_sim_granularity: 0.1
+ path_distance_bias: 32.0
+ goal_distance_bias: 24.0
+ occdist_scale: 0.02
+ forward_point_distance: 0.325
+ use_dwa: true
+ dwa_padding_inaccuracies: 0.1
+ max_allowed_time_female: 0.0
+ oscillation_max_iterations: 1800
+ oscillation_max_distance: 0.02
+ use_velocity_scaled_lookahead_dist: false
+ min_approach_linear_velocity: 0.1
+ approach_velocity_scaling_dist: 1.0
+ critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+ rotate_to_goal:
+ slowing_factor: 5.0
+ lookahead_time: -1.0
+ base_obstacle:
+ scale: 0.02
+ max_scaling_factor: 0.02
+ forward_point_distance: 0.325
+ goal_align:
+ scale: 24.0
+ forward_point_distance: 0.325
+ path_align:
+ scale: 32.0
+ forward_point_distance: 0.325
+ max_allowed_time_female: 0.0
+ path_dist:
+ scale: 32.0
+ max_allowed_time_female: 0.0
+ goal_dist:
+ scale: 24.0
+ max_allowed_time_female: 0.0
+ prune_plan: true
+ prune_distance: 1.5
+ debug_trajectory_details: false
+ publish_evaluation: true
+ publish_scored_sampling_policies: false
+ publish_trajectories: false
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/config/global_costmap_params.yaml b/jetson/ros2_ws/src/saltybot_nav2_slam/config/global_costmap_params.yaml
new file mode 100644
index 0000000..58df832
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/config/global_costmap_params.yaml
@@ -0,0 +1,36 @@
+global_costmap:
+ global_costmap:
+ ros__parameters:
+ update_frequency: 5.0
+ publish_frequency: 2.0
+ global_frame: map
+ robot_base_frame: base_link
+ use_sim_time: false
+ rolling_window: false
+ robot_radius: 0.35
+ plugins:
+ - name: static_layer
+ type: nav2_costmap_2d::StaticLayer
+ map_subscribe_transient_local: true
+ enabled: true
+ - name: obstacle_layer
+ type: nav2_costmap_2d::ObstacleLayer
+ enabled: true
+ observation_sources: scan
+ scan:
+ topic: /scan
+ max_obstacle_height: 2.5
+ min_obstacle_height: 0.0
+ clearing: true
+ marking: true
+ data_type: LaserScan
+ - name: inflation_layer
+ type: nav2_costmap_2d::InflationLayer
+ enabled: true
+ inflation_radius: 0.55
+ cost_scaling_factor: 10.0
+ inflate_unknown: false
+ inflate_around_unknown: true
+ resolution: 0.05
+ track_unknown_space: true
+ unknown_cost_value: -1
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/config/local_costmap_params.yaml b/jetson/ros2_ws/src/saltybot_nav2_slam/config/local_costmap_params.yaml
new file mode 100644
index 0000000..a21dd07
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/config/local_costmap_params.yaml
@@ -0,0 +1,51 @@
+local_costmap:
+ local_costmap:
+ ros__parameters:
+ update_frequency: 10.0
+ publish_frequency: 5.0
+ global_frame: odom
+ robot_base_frame: base_link
+ use_sim_time: false
+ rolling_window: true
+ width: 3
+ height: 3
+ resolution: 0.05
+ robot_radius: 0.35
+ plugins:
+ - name: obstacle_layer
+ type: nav2_costmap_2d::ObstacleLayer
+ enabled: true
+ observation_sources: scan camera_depth
+ scan:
+ topic: /scan
+ max_obstacle_height: 2.5
+ min_obstacle_height: 0.0
+ clearing: true
+ marking: true
+ data_type: LaserScan
+ raytrace_max_range: 10.0
+ raytrace_min_range: 0.0
+ expected_update_rate: 5.5
+ observation_persistence: 0.0
+ camera_depth:
+ topic: /camera/depth/color/points
+ max_obstacle_height: 2.5
+ min_obstacle_height: 0.0
+ clearing: false
+ marking: true
+ data_type: PointCloud2
+ sensor_frame: camera_link
+ expected_update_rate: 15.0
+ observation_persistence: 0.5
+ inf_is_valid: false
+ filter: passthrough
+ filter_value: 5.0
+ - name: inflation_layer
+ type: nav2_costmap_2d::InflationLayer
+ enabled: true
+ inflation_radius: 0.55
+ cost_scaling_factor: 10.0
+ inflate_unknown: true
+ inflate_around_unknown: false
+ track_unknown_space: true
+ unknown_cost_value: 0
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/config/nav2_params.yaml b/jetson/ros2_ws/src/saltybot_nav2_slam/config/nav2_params.yaml
new file mode 100644
index 0000000..35209b8
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/config/nav2_params.yaml
@@ -0,0 +1,219 @@
+amcl:
+ ros__parameters:
+ use_sim_time: false
+ alpha1: 0.2
+ alpha2: 0.2
+ alpha3: 0.2
+ alpha4: 0.2
+ alpha5: 0.2
+ base_frame_id: "base_link"
+ beam_search_increment: 0.1
+ do_beamskip: false
+ global_frame_id: "map"
+ lambda_short: 0.1
+ laser_likelihood_max_dist: 2.0
+ laser_model_type: "likelihood_field"
+ max_beams: 60
+ max_particles: 2000
+ min_particles: 500
+ odom_frame_id: "odom"
+ pf_err: 0.05
+ pf_z: 0.99
+ recovery_alpha_fast: 0.0
+ recovery_alpha_slow: 0.0
+ resample_interval: 1
+ robot_model_type: "differential"
+ save_pose_rate: 0.5
+ sigma_hit: 0.2
+ sigma_short: 0.05
+ tf_broadcast: true
+ transform_tolerance: 1.0
+ update_min_a: 0.2
+ update_min_d: 0.25
+ z_hit: 0.5
+ z_max: 0.05
+ z_rand: 0.5
+ z_short: 0.05
+
+amcl_map_client:
+ ros__parameters:
+ use_sim_time: false
+
+amcl_rclcpp_node:
+ ros__parameters:
+ use_sim_time: false
+
+bt_navigator:
+ ros__parameters:
+ use_sim_time: false
+ global_frame: map
+ robot_base_frame: base_link
+ odom_topic: /odom
+ enable_groot_monitoring: true
+ groot_zmq_publisher_port: 1666
+ groot_zmq_server_port: 1667
+ default_nav_through_poses_bt_xml: $(find-pkg-share nav2_bt_navigator)/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml
+ default_nav_to_pose_bt_xml: $(find-pkg-share nav2_bt_navigator)/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml
+ plugin_lib_names:
+ - nav2_compute_path_to_pose_action_bt_node
+ - nav2_compute_path_through_poses_action_bt_node
+ - nav2_follow_path_action_bt_node
+ - nav2_spin_action_bt_node
+ - nav2_wait_action_bt_node
+ - nav2_assisted_teleop_action_bt_node
+ - nav2_back_up_action_bt_node
+ - nav2_drive_on_heading_bt_node
+ - nav2_clear_costmap_service_bt_node
+ - nav2_is_stuck_condition_bt_node
+ - nav2_goal_updated_condition_bt_node
+ - nav2_initial_pose_received_condition_bt_node
+ - nav2_reinitialize_global_localization_service_bt_node
+ - nav2_rate_controller_bt_node
+ - nav2_distance_controller_bt_node
+ - nav2_speed_controller_bt_node
+ - nav2_truncate_path_action_bt_node
+ - nav2_truncate_path_local_action_bt_node
+ - nav2_remove_passed_goals_action_bt_node
+ - nav2_planner_selector_bt_node
+ - nav2_controller_selector_bt_node
+ - nav2_goal_checker_selector_bt_node
+
+bt_navigator_rclcpp_node:
+ ros__parameters:
+ use_sim_time: false
+
+controller_server:
+ ros__parameters:
+ use_sim_time: false
+ controller_frequency: 20.0
+ min_x_velocity_threshold: 0.001
+ min_y_velocity_threshold: 0.5
+ min_theta_velocity_threshold: 0.001
+ failure_tolerance: 0.3
+ progress_checker_plugin: "progress_checker"
+ goal_checker_plugins: ["general_goal_checker"]
+ controller_plugins: ["FollowPath"]
+
+ progress_checker:
+ plugin: "nav2_core::SimpleProgressChecker"
+ required_movement_radius: 0.5
+ movement_time_allowance: 10.0
+
+ general_goal_checker:
+ stateful: True
+ plugin: "nav2_core::SimpleGoalChecker"
+ xy_goal_tolerance: 0.25
+ yaw_goal_tolerance: 0.25
+
+ FollowPath:
+ plugin: "dwb_core::DWBLocalPlanner"
+ debug_trajectory_details: true
+ min_vel_x: 0.0
+ max_vel_x: 5.5
+ max_vel_theta: 3.0
+ min_speed_xy: 0.0
+ max_speed_xy: 5.5
+ acc_lim_x: 2.5
+ acc_lim_theta: 2.5
+ decel_lim_x: -2.5
+ decel_lim_theta: -2.5
+ vx_samples: 20
+ vtheta_samples: 40
+ sim_time: 1.7
+ linear_granularity: 0.05
+ angular_granularity: 0.1
+ transform_tolerance: 0.2
+ trans_stopped_velocity: 0.25
+ short_circuit_trajectory_evaluation: true
+ stateful: True
+ critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+ BaseObstacle.scale: 0.02
+ PathAlign.scale: 32.0
+ GoalAlign.scale: 24.0
+ PathDist.scale: 32.0
+ GoalDist.scale: 24.0
+ RotateToGoal.scale: 32.0
+
+controller_server_rclcpp_node:
+ ros__parameters:
+ use_sim_time: false
+
+planner_server:
+ ros__parameters:
+ expected_planner_frequency: 20.0
+ use_sim_time: false
+ planner_plugins: ["GridBased"]
+ GridBased:
+ plugin: "nav2_navfn_planner/NavfnPlanner"
+ tolerance: 0.5
+ use_astar: true
+ allow_unknown: true
+
+planner_server_rclcpp_node:
+ ros__parameters:
+ use_sim_time: false
+
+behavior_server:
+ ros__parameters:
+ costmap_topic: local_costmap/costmap_raw
+ footprint_topic: local_costmap/published_footprint
+ cycle_frequency: 10.0
+ behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
+ spin:
+ plugin: "nav2_behaviors/Spin"
+ backup:
+ plugin: "nav2_behaviors/BackUp"
+ drive_on_heading:
+ plugin: "nav2_behaviors/DriveOnHeading"
+ assisted_teleop:
+ plugin: "nav2_behaviors/AssistedTeleop"
+ wait:
+ plugin: "nav2_behaviors/Wait"
+ global_frame: odom
+ robot_base_frame: base_link
+ transform_timeout: 0.1
+ use_sim_time: false
+ simulate_ahead_time: 2.0
+ max_rotations: 1.0
+ max_backup_dist: 0.15
+ backup_speed: 0.5
+
+behavior_server_rclcpp_node:
+ ros__parameters:
+ use_sim_time: false
+
+robot_state_publisher:
+ ros__parameters:
+ use_sim_time: false
+
+lifecycle_manager_navigation:
+ ros__parameters:
+ use_sim_time: false
+ autostart: true
+ node_names: ['controller_server', 'planner_server', 'behavior_server', 'bt_navigator']
+
+lifecycle_manager_localization:
+ ros__parameters:
+ use_sim_time: false
+ autostart: true
+ node_names: ['amcl']
+
+map_server:
+ ros__parameters:
+ use_sim_time: false
+ yaml_filename: "map.yaml"
+
+velocity_smoother:
+ ros__parameters:
+ use_sim_time: false
+ smoothing_frequency: 20.0
+ scale_velocities: false
+ feedback: "odometry"
+ max_velocity: [5.5, 0.0, 3.0]
+ min_velocity: [-5.5, 0.0, -3.0]
+ max_accel: [2.5, 0.0, 2.5]
+ max_decel: [-2.5, 0.0, -2.5]
+ odom_topic: "odom"
+ odom_duration: 0.1
+ deadband_velocity: [0.0, 0.0, 0.0]
+ velocity_timeout: 1.0
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/config/slam_toolbox_params.yaml b/jetson/ros2_ws/src/saltybot_nav2_slam/config/slam_toolbox_params.yaml
new file mode 100644
index 0000000..7344f25
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/config/slam_toolbox_params.yaml
@@ -0,0 +1,58 @@
+slam_toolbox:
+ ros__parameters:
+ mode: mapping
+ async_mode: true
+ use_scan_matching: true
+ use_scan_bamatching: true
+ minimum_time_interval: 0.5
+ minimum_travel_distance: 0.2
+ minimum_rotation_deg: 5.0
+ correlation_search_space_dimension: 0.5
+ correlation_search_space_resolution: 0.05
+ correlation_search_space_smear_deviation: 0.1
+ correlation_search_space_std_dev_ratio: 0.5
+ loop_search_space_dimension: 8.0
+ loop_search_space_resolution: 0.05
+ scan_buffer_size: 10
+ scan_buffer_max_scan_distance: 12.0
+ distance_variance_penalty: 0.5
+ angle_variance_penalty: 1.0
+ fine_search_angle_offset: 0.00349
+ coarse_search_angle_offset: 0.349
+ coarse_angle_search_step_size: 0.0349
+ fine_angle_search_step_size: 0.00349
+ solver_plugin: solver_plugins::CeresSolver
+ ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
+ ceres_preconditioner: SCHUR_JACOBI
+ ceres_trust_strategy: LEVENBERG_MARQUARDT
+ ceres_dogleg_type: TRADITIONAL_DOGLEG
+ do_loop_closing: true
+ loop_match_minimum_chain_size: 10
+ loop_match_maximum_variance_queue_size: 10
+ loop_match_minimum_response_fine: 0.1
+ loop_match_minimum_response_coarse: 0.3
+ minimum_score_to_accept_loop_closure: 0.07
+ do_final_optimization: true
+ final_optimization_particle_filter_size: 800
+ final_optimization_min_particles: 400
+ final_optimization_max_particles: 2000
+ final_optimization_threshold_metric_improvement: 0.0002
+ add_loops_as_edges: false
+ num_for_scan_matching: 0
+ icp_iterations: 10
+ interactive_mode: false
+ print_timing_information: false
+ map_frame: map
+ odom_frame: odom
+ base_frame: base_link
+ scan_topic: /scan
+ publish_tf: true
+ tf_buffer_duration: 30.0
+ transform_timeout: 0.2
+ queue_size: 10
+ throttle_scans: 1
+ use_map_saver: true
+ map_start_at_dock: true
+ map_start_pose: [0.0, 0.0, 0.0]
+ rollout_velocity_smoothing_factor: 0.07
+ force_turtlebot_rep: false
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/launch/depth_to_costmap.launch.py b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/depth_to_costmap.launch.py
new file mode 100644
index 0000000..20851b4
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/depth_to_costmap.launch.py
@@ -0,0 +1,28 @@
+"""RealSense Depth to Costmap Integration"""
+
+from launch import LaunchDescription
+from launch.actions import DeclareLaunchArgument
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import Node
+
+
+def generate_launch_description():
+ use_sim_time = LaunchConfiguration('use_sim_time')
+
+ return LaunchDescription([
+ DeclareLaunchArgument('use_sim_time', default_value='false'),
+
+ Node(
+ package='depth_image_proc',
+ executable='convert_node',
+ name='depth_image_converter',
+ namespace='camera',
+ remappings=[
+ ('image_rect', '/camera/aligned_depth_to_color/image_raw'),
+ ('camera_info', '/camera/color/camera_info'),
+ ('points', '/camera/depth/color/points'),
+ ],
+ parameters=[{'use_sim_time': use_sim_time}],
+ output='screen',
+ ),
+ ])
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/launch/nav2_slam_bringup.launch.py b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/nav2_slam_bringup.launch.py
new file mode 100644
index 0000000..25abd20
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/nav2_slam_bringup.launch.py
@@ -0,0 +1,66 @@
+"""Nav2 SLAM Bringup for SaltyBot (Issue #422)"""
+
+import os
+from launch import LaunchDescription
+from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration
+from ament_index_python.packages import get_package_share_directory
+
+
+def generate_launch_description():
+ nav2_slam_dir = get_package_share_directory('saltybot_nav2_slam')
+ bringup_dir = get_package_share_directory('saltybot_bringup')
+
+ nav2_params = os.path.join(nav2_slam_dir, 'config', 'nav2_params.yaml')
+ slam_params = os.path.join(nav2_slam_dir, 'config', 'slam_toolbox_params.yaml')
+
+ return LaunchDescription([
+ DeclareLaunchArgument('use_sim_time', default_value='false'),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(bringup_dir, 'launch', 'sensors.launch.py')
+ ),
+ launch_arguments={'use_sim_time': LaunchConfiguration('use_sim_time')}.items(),
+ ),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(nav2_slam_dir, 'launch', 'odometry_bridge.launch.py')
+ ),
+ launch_arguments={'use_sim_time': LaunchConfiguration('use_sim_time')}.items(),
+ ),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(nav2_slam_dir, 'launch', 'nav2_slam_integrated.launch.py')
+ ),
+ launch_arguments={
+ 'slam_params_file': slam_params,
+ 'use_sim_time': LaunchConfiguration('use_sim_time'),
+ }.items(),
+ ),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(nav2_slam_dir, 'launch', 'depth_to_costmap.launch.py')
+ ),
+ launch_arguments={'use_sim_time': LaunchConfiguration('use_sim_time')}.items(),
+ ),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(
+ get_package_share_directory('nav2_bringup'),
+ 'launch', 'navigation_launch.py'
+ )
+ ),
+ launch_arguments={
+ 'use_sim_time': LaunchConfiguration('use_sim_time'),
+ 'params_file': nav2_params,
+ 'autostart': 'true',
+ 'map_subscribe_transient_local': 'true',
+ }.items(),
+ ),
+ ])
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/launch/nav2_slam_integrated.launch.py b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/nav2_slam_integrated.launch.py
new file mode 100644
index 0000000..3c1f7b2
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/nav2_slam_integrated.launch.py
@@ -0,0 +1,35 @@
+"""SLAM Toolbox integrated launch for SaltyBot"""
+
+import os
+from launch import LaunchDescription
+from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration
+from ament_index_python.packages import get_package_share_directory
+
+
+def generate_launch_description():
+ slam_share = get_package_share_directory('slam_toolbox')
+ nav2_slam_dir = get_package_share_directory('saltybot_nav2_slam')
+
+ slam_params = LaunchConfiguration('slam_params_file')
+ use_sim_time = LaunchConfiguration('use_sim_time')
+
+ return LaunchDescription([
+ DeclareLaunchArgument(
+ 'slam_params_file',
+ default_value=os.path.join(nav2_slam_dir, 'config', 'slam_toolbox_params.yaml'),
+ ),
+
+ DeclareLaunchArgument('use_sim_time', default_value='false'),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(slam_share, 'launch', 'online_async_launch.py')
+ ),
+ launch_arguments={
+ 'params_file': slam_params,
+ 'use_sim_time': use_sim_time,
+ }.items(),
+ ),
+ ])
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/launch/odometry_bridge.launch.py b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/odometry_bridge.launch.py
new file mode 100644
index 0000000..0ec8e29
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/launch/odometry_bridge.launch.py
@@ -0,0 +1,36 @@
+"""VESC Telemetry to Odometry Bridge"""
+
+import os
+from launch import LaunchDescription
+from launch.actions import DeclareLaunchArgument
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import Node
+from ament_index_python.packages import get_package_share_directory
+
+
+def generate_launch_description():
+ use_sim_time = LaunchConfiguration('use_sim_time')
+
+ return LaunchDescription([
+ DeclareLaunchArgument('use_sim_time', default_value='false'),
+
+ Node(
+ package='saltybot_nav2_slam',
+ executable='vesc_odometry_bridge',
+ name='vesc_odometry_bridge',
+ parameters=[{
+ 'use_sim_time': use_sim_time,
+ 'vesc_state_topic': '/vesc/state',
+ 'odometry_topic': '/odom',
+ 'odom_frame_id': 'odom',
+ 'base_frame_id': 'base_link',
+ 'update_frequency': 50,
+ 'wheel_base': 0.35,
+ 'wheel_radius': 0.10,
+ 'max_rpm': 60000,
+ 'publish_tf': True,
+ 'tf_queue_size': 10,
+ }],
+ output='screen',
+ ),
+ ])
diff --git a/jetson/ros2_ws/src/saltybot_nav2_slam/package.xml b/jetson/ros2_ws/src/saltybot_nav2_slam/package.xml
new file mode 100644
index 0000000..2e1ce41
--- /dev/null
+++ b/jetson/ros2_ws/src/saltybot_nav2_slam/package.xml
@@ -0,0 +1,39 @@
+
+
+