diff --git a/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml b/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml
index 5358f15..a53687e 100644
--- a/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml
+++ b/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml
@@ -23,7 +23,7 @@ ekf_filter_node_odom:
odom0_differential: false
odom0_relative: false
- imu0: imu
+ imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
false, false, false,
@@ -85,7 +85,7 @@ ekf_filter_node_map:
odom1_differential: false
odom1_relative: false
- imu0: imu
+ imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
false, false, false,
@@ -121,7 +121,7 @@ navsat_transform:
magnetic_declination_radians: 0.0
yaw_offset: 0.0
zero_altitude: true
- broadcast_utm_transform: true
+ broadcast_cartesian_transform: true
publish_filtered_gps: true
use_odometry_yaw: true
- wait_for_datum: false
+ wait_for_datum: false
diff --git a/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc b/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc
index bb578c7..e97245c 100644
--- a/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc
+++ b/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc
@@ -22,9 +22,12 @@ displays:
visible: true
collapsed: false
custom_sources:
- []
+ - base_url: https://tiles.stadiamaps.com/tiles/alidade_satellite/{level}/{x}/{y}.png?api_key=api_key
+ max_zoom: 15
+ name: Stadia (alidade_satellite)
+ type: wmts
bing_api_key: ""
- source: Bing Maps (terrain)
+ source: Stadia (alidade_satellite)
- type: mapviz_plugins/point_click_publisher
name: new display
config:
diff --git a/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml b/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml
index ec47f72..63099a0 100644
--- a/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml
+++ b/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml
@@ -13,80 +13,24 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
+ wait_for_service_timeout: 1000
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
- plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
+ plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
navigate_through_poses:
- plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator"
+ plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
- plugin_lib_names:
- - nav2_compute_path_to_pose_action_bt_node
- - nav2_compute_path_through_poses_action_bt_node
- - nav2_smooth_path_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_reached_condition_bt_node
- - nav2_goal_updated_condition_bt_node
- - nav2_globally_updated_goal_condition_bt_node
- - nav2_is_path_valid_condition_bt_node
- - nav2_are_error_codes_active_condition_bt_node
- - nav2_would_a_controller_recovery_help_condition_bt_node
- - nav2_would_a_planner_recovery_help_condition_bt_node
- - nav2_would_a_smoother_recovery_help_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_goal_updater_node_bt_node
- - nav2_recovery_node_bt_node
- - nav2_pipeline_sequence_bt_node
- - nav2_round_robin_node_bt_node
- - nav2_transform_available_condition_bt_node
- - nav2_time_expired_condition_bt_node
- - nav2_path_expiring_timer_condition
- - nav2_distance_traveled_condition_bt_node
- - nav2_single_trigger_bt_node
- - nav2_goal_updated_controller_bt_node
- - nav2_is_battery_low_condition_bt_node
- - nav2_navigate_through_poses_action_bt_node
- - nav2_navigate_to_pose_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
- - nav2_controller_cancel_bt_node
- - nav2_path_longer_on_approach_bt_node
- - nav2_wait_cancel_bt_node
- - nav2_spin_cancel_bt_node
- - nav2_back_up_cancel_bt_node
- - nav2_assisted_teleop_cancel_bt_node
- - nav2_drive_on_heading_cancel_bt_node
- - nav2_is_battery_charging_condition_bt_node
+
+ # plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
+ # Built-in plugins are added automatically
+ # plugin_lib_names: []
+
error_code_name_prefixes:
- - assisted_teleop
- - backup
- compute_path
- - dock_robot
- - drive_on_heading
- follow_path
- - nav_thru_poses
- - nav_to_pose
- - route
- - spin
- - undock_robot
- - wait
controller_server:
ros__parameters:
@@ -117,46 +61,102 @@ controller_server:
yaw_goal_tolerance: 0.25
# DWB parameters
FollowPath:
- plugin: "dwb_core::DWBLocalPlanner"
- debug_trajectory_details: True
- min_vel_x: 0.0
- min_vel_y: 0.0
- max_vel_x: 0.26
- max_vel_y: 0.0
- max_vel_theta: 1.0
- min_speed_xy: 0.0
- max_speed_xy: 0.26
- min_speed_theta: 0.0
- # Add high threshold velocity for turtlebot 3 issue.
- # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
- acc_lim_x: 2.5
- acc_lim_y: 0.0
- acc_lim_theta: 3.2
- decel_lim_x: -2.5
- decel_lim_y: 0.0
- decel_lim_theta: -3.2
- vx_samples: 20
- vy_samples: 5
- vtheta_samples: 20
- sim_time: 1.7
- linear_granularity: 0.05
- angular_granularity: 0.025
- transform_tolerance: 0.2
- xy_goal_tolerance: 0.25
- 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
- PathAlign.forward_point_distance: 0.1
- GoalAlign.scale: 24.0
- GoalAlign.forward_point_distance: 0.1
- PathDist.scale: 32.0
- GoalDist.scale: 24.0
- RotateToGoal.scale: 32.0
- RotateToGoal.slowing_factor: 5.0
- RotateToGoal.lookahead_time: -1.0
+ plugin: "nav2_mppi_controller::MPPIController"
+ time_steps: 56
+ model_dt: 0.05
+ batch_size: 2000
+ ax_max: 3.0
+ ax_min: -3.0
+ ay_max: 3.0
+ ay_min: -3.0
+ az_max: 3.5
+ vx_std: 0.2
+ vy_std: 0.2
+ wz_std: 0.4
+ vx_max: 0.5
+ vx_min: -0.35
+ vy_max: 0.5
+ wz_max: 1.9
+ iteration_count: 1
+ prune_distance: 1.7
+ transform_tolerance: 0.1
+ temperature: 0.3
+ gamma: 0.015
+ motion_model: "DiffDrive"
+ visualize: true
+ regenerate_noises: true
+ TrajectoryVisualizer:
+ trajectory_step: 5
+ time_step: 3
+ AckermannConstraints:
+ min_turning_r: 0.2
+ critics:
+ [
+ "ConstraintCritic",
+ "CostCritic",
+ "GoalCritic",
+ "GoalAngleCritic",
+ "PathAlignCritic",
+ "PathFollowCritic",
+ "PathAngleCritic",
+ "PreferForwardCritic",
+ ]
+ ConstraintCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 4.0
+ GoalCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 5.0
+ threshold_to_consider: 1.4
+ GoalAngleCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 3.0
+ threshold_to_consider: 0.5
+ PreferForwardCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 5.0
+ threshold_to_consider: 0.5
+ CostCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 3.81
+ near_collision_cost: 253
+ critical_cost: 300.0
+ consider_footprint: false
+ collision_cost: 1000000.0
+ near_goal_distance: 1.0
+ trajectory_point_step: 2
+ PathAlignCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 14.0
+ max_path_occupancy_ratio: 0.05
+ trajectory_point_step: 4
+ threshold_to_consider: 0.5
+ offset_from_furthest: 20
+ use_path_orientations: false
+ PathFollowCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 5.0
+ offset_from_furthest: 5
+ threshold_to_consider: 1.4
+ PathAngleCritic:
+ enabled: true
+ cost_power: 1
+ cost_weight: 2.0
+ offset_from_furthest: 4
+ threshold_to_consider: 0.5
+ max_angle_to_furthest: 1.0
+ mode: 0
+ # TwirlingCritic:
+ # enabled: true
+ # twirling_cost_power: 1
+ # twirling_cost_weight: 10.0
# GPS WPF CHANGE: Remove static layer
local_costmap:
@@ -199,7 +199,6 @@ local_costmap:
always_send_full_costmap: True
# GPS WPF CHANGE: Remove static layer
-# GPS WPF CHANGE: Set rolling global costmap with 50x50 size. See note below
global_costmap:
global_costmap:
ros__parameters:
@@ -215,6 +214,8 @@ global_costmap:
rolling_window: True
width: 50
height: 50
+ # origin_x: 0.0
+ # origin_y: 0.0
track_unknown_space: true
# no static map
plugins: ["obstacle_layer", "inflation_layer"]
@@ -253,13 +254,16 @@ map_saver:
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: True
+ service_introspection_mode: "disabled"
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
+ costmap_update_timeout: 1.0
+ service_introspection_mode: "disabled"
GridBased:
- plugin: "nav2_navfn_planner/NavfnPlanner"
+ plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
@@ -271,6 +275,9 @@ smoother_server:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
max_its: 1000
+ refinement_num: 2
+ # True for Hybrid A* or State Lattice to not smooth over directional changes
+ enforce_path_inversion: True
do_refinement: True
behavior_server:
@@ -280,17 +287,24 @@ behavior_server:
local_footprint_topic: local_costmap/published_footprint
global_footprint_topic: global_costmap/published_footprint
cycle_frequency: 10.0
- behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
+ behavior_plugins:
+ ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin:
- plugin: "nav2_behaviors/Spin"
+ plugin: "nav2_behaviors::Spin"
backup:
- plugin: "nav2_behaviors/BackUp"
+ plugin: "nav2_behaviors::BackUp"
+ acceleration_limit: 2.5
+ deceleration_limit: -2.5
+ minimum_speed: 0.10
drive_on_heading:
- plugin: "nav2_behaviors/DriveOnHeading"
+ plugin: "nav2_behaviors::DriveOnHeading"
+ acceleration_limit: 2.5
+ deceleration_limit: -2.5
+ minimum_speed: 0.10
wait:
- plugin: "nav2_behaviors/Wait"
+ plugin: "nav2_behaviors::Wait"
assisted_teleop:
- plugin: "nav2_behaviors/AssistedTeleop"
+ plugin: "nav2_behaviors::AssistedTeleop"
local_frame: odom
global_frame: map
robot_base_frame: base_link
@@ -304,6 +318,7 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
+ service_introspection_mode: "disabled"
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
@@ -323,3 +338,102 @@ velocity_smoother:
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0
+
+collision_monitor:
+ ros__parameters:
+ base_frame_id: "base_footprint"
+ odom_frame_id: "odom"
+ cmd_vel_in_topic: "cmd_vel_smoothed"
+ cmd_vel_out_topic: "cmd_vel"
+ state_topic: "collision_monitor_state"
+ transform_tolerance: 0.2
+ source_timeout: 1.0
+ base_shift_correction: True
+ stop_pub_timeout: 2.0
+ # Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
+ # and robot footprint for "approach" action type.
+ polygons: ["FootprintApproach"]
+ FootprintApproach:
+ type: "polygon"
+ action_type: "approach"
+ footprint_topic: "/local_costmap/published_footprint"
+ time_before_collision: 2.0
+ simulation_time_step: 0.1
+ min_points: 6
+ visualize: False
+ enabled: True
+ observation_sources: ["scan"]
+ scan:
+ type: "scan"
+ topic: "scan"
+ min_height: 0.15
+ max_height: 2.0
+ enabled: True
+
+docking_server:
+ ros__parameters:
+ controller_frequency: 50.0
+ initial_perception_timeout: 5.0
+ wait_charge_timeout: 5.0
+ dock_approach_timeout: 30.0
+ undock_linear_tolerance: 0.05
+ undock_angular_tolerance: 0.1
+ max_retries: 3
+ base_frame: "base_link"
+ fixed_frame: "odom"
+ dock_prestaging_tolerance: 0.5
+ service_introspection_mode: "disabled"
+
+ # Types of docks
+ dock_plugins: ["simple_charging_dock"]
+ simple_charging_dock:
+ plugin: "opennav_docking::SimpleChargingDock"
+ docking_threshold: 0.05
+ staging_x_offset: -0.7
+ use_external_detection_pose: true
+ use_battery_status: false # true
+ use_stall_detection: false # true
+ dock_direction: "forward"
+
+ external_detection_timeout: 1.0
+ external_detection_translation_x: -0.18
+ external_detection_translation_y: 0.0
+ external_detection_rotation_roll: -1.57
+ external_detection_rotation_pitch: -1.57
+ external_detection_rotation_yaw: 0.0
+ filter_coef: 0.1
+
+ # Dock instances
+ # The following example illustrates configuring dock instances.
+ # docks: ['home_dock'] # Input your docks here
+ # home_dock:
+ # type: 'simple_charging_dock'
+ # frame: map
+ # pose: [0.0, 0.0, 0.0]
+
+ controller:
+ k_phi: 3.0
+ k_delta: 2.0
+ v_linear_min: 0.15
+ v_linear_max: 0.15
+ use_collision_detection: true
+ costmap_topic: "/local_costmap/costmap_raw"
+ footprint_topic: "/local_costmap/published_footprint"
+ transform_tolerance: 0.1
+ projection_time: 5.0
+ simulation_step: 0.1
+ dock_collision_threshold: 0.3
+
+loopback_simulator:
+ ros__parameters:
+ base_frame_id: "base_footprint"
+ 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.02
+ scan_range_min: 0.05
+ scan_range_max: 30.0
+ scan_angle_min: -3.1415
+ scan_angle_max: 3.1415
+ scan_angle_increment: 0.02617
+ scan_use_inf: true
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py b/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py
index 4bf4449..e14f83c 100644
--- a/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py
+++ b/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py
@@ -1,5 +1,5 @@
# Copyright (c) 2018 Intel Corporation
-#
+# Copyright (C) 2024 Stevedan Ogochukwu Omodolor Omodia
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
@@ -16,67 +16,90 @@
from ament_index_python.packages import get_package_share_directory
+
from launch import LaunchDescription
-from launch.actions import ExecuteProcess, SetEnvironmentVariable
+from launch.actions import (
+ DeclareLaunchArgument,
+ IncludeLaunchDescription,
+ ExecuteProcess,
+)
+
+from launch.conditions import IfCondition
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration
+
from launch_ros.actions import Node
def generate_launch_description():
- # Get the launch directory
- gps_wpf_dir = get_package_share_directory(
- "nav2_gps_waypoint_follower_demo")
- launch_dir = os.path.join(gps_wpf_dir, 'launch')
- world = os.path.join(gps_wpf_dir, "worlds", "sonoma_raceway.world")
-
- urdf = os.path.join(gps_wpf_dir, 'urdf', 'turtlebot3_waffle_gps.urdf')
- with open(urdf, 'r') as infp:
- robot_description = infp.read()
+ sim_dir = get_package_share_directory("nav2_minimal_tb3_sim")
+ tutorial_dir = get_package_share_directory("nav2_gps_waypoint_follower_demo")
- models_dir = os.path.join(gps_wpf_dir, "models")
- models_dir += os.pathsep + \
- f"/opt/ros/{os.getenv('ROS_DISTRO')}/share/turtlebot3_gazebo/models"
- set_gazebo_model_path_cmd = None
+ # Create the launch configuration variables
+ use_sim_time = LaunchConfiguration("use_sim_time")
- if 'GAZEBO_MODEL_PATH' in os.environ:
- gazebo_model_path = os.environ['GAZEBO_MODEL_PATH'] + \
- os.pathsep + models_dir
- set_gazebo_model_path_cmd = SetEnvironmentVariable(
- "GAZEBO_MODEL_PATH", gazebo_model_path)
- else:
- set_gazebo_model_path_cmd = SetEnvironmentVariable(
- "GAZEBO_MODEL_PATH", models_dir)
+ # Decalre the launch arguments
+ declare_use_sim_time_cmd = DeclareLaunchArgument(
+ "use_sim_time",
+ default_value="True",
+ description="Use simulation (Gazebo) clock if true",
+ )
- set_tb3_model_cmd = SetEnvironmentVariable("TURTLEBOT3_MODEL", "waffle")
+ world_sdf = os.path.join(tutorial_dir, "worlds", "tb3_sonoma_raceway.sdf.xacro")
+ robot_sdf = os.path.join(sim_dir, "urdf", "gz_waffle_gps.sdf.xacro")
- # Specify the actions
- start_gazebo_server_cmd = ExecuteProcess(
- cmd=['gzserver', '-s', 'libgazebo_ros_init.so',
- '-s', 'libgazebo_ros_factory.so', world],
- cwd=[launch_dir], output='both')
+ urdf = os.path.join(sim_dir, "urdf", "turtlebot3_waffle_gps.urdf")
+ with open(urdf, "r") as infp:
+ robot_description = infp.read()
- start_gazebo_client_cmd = ExecuteProcess(
- cmd=['gzclient'],
- cwd=[launch_dir], output='both')
+ gazebo_server = ExecuteProcess(
+ cmd=["gz", "sim", "-r", "-s", world_sdf],
+ output="screen",
+ )
+
+ gazebo_client = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(
+ get_package_share_directory("ros_gz_sim"), "launch", "gz_sim.launch.py"
+ )
+ ),
+ launch_arguments={"gz_args": ["-v4 -g "]}.items(),
+ )
+
+ gz_robot = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(sim_dir, "launch", "spawn_tb3_gps.launch.py")
+ ),
+ launch_arguments={
+ "use_sim_time": use_sim_time,
+ "robot_sdf": robot_sdf,
+ "x_pose": "2.0",
+ "y_pose": "-2.5",
+ "z_pose": "0.33",
+ "roll": "0.0",
+ "pitch": "0.0",
+ "yaw": "0.0",
+ }.items(),
+ )
start_robot_state_publisher_cmd = Node(
- package='robot_state_publisher',
- executable='robot_state_publisher',
- name='robot_state_publisher',
- output='both',
- parameters=[{'robot_description': robot_description}])
+ package="robot_state_publisher",
+ executable="robot_state_publisher",
+ name="robot_state_publisher",
+ output="screen",
+ parameters=[
+ {"use_sim_time": use_sim_time, "robot_description": robot_description}
+ ],
+ )
- # Create the launch description and populate
ld = LaunchDescription()
- # Set gazebo up to find models properly
- ld.add_action(set_gazebo_model_path_cmd)
- ld.add_action(set_tb3_model_cmd)
+ # Declare the launch options
+ ld.add_action(declare_use_sim_time_cmd)
- # simulator launch
- ld.add_action(start_gazebo_server_cmd)
- ld.add_action(start_gazebo_client_cmd)
+ ld.add_action(gz_robot)
+ ld.add_action(gazebo_server)
+ ld.add_action(gazebo_client)
- # robot state publisher launch
ld.add_action(start_robot_state_publisher_cmd)
-
return ld
diff --git a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.config b/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.config
deleted file mode 100755
index 6543f64..0000000
--- a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.config
+++ /dev/null
@@ -1,19 +0,0 @@
-
-
-
- turtlebot_waffle_gps
- 2.0
- model.sdf
-
-
- Taehun Lim(Darby)
- thlim@robotis.com
-
- Melih Erdogan(mlherd)
- h.meliherdogan@gmail.com
-
-
-
- TurtleBot3 Waffle with a gps sensor
-
-
diff --git a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.sdf b/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.sdf
deleted file mode 100755
index 2479342..0000000
--- a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.sdf
+++ /dev/null
@@ -1,561 +0,0 @@
-
-
-
-
-
-
-
-
- 0.0 0.0 0.0 0.0 0.0 0.0
-
-
-
-
-
-
- -0.064 0 0.048 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 1.0
-
-
-
- -0.064 0 0.048 0 0 0
-
-
- 0.265 0.265 0.089
-
-
-
-
-
- -0.064 0 0 0 0 0
-
-
- model://turtlebot3_common/meshes/waffle_base.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
- true
- 200
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
-
- false
-
-
- ~/out:=imu
-
-
-
-
-
-
-
-
- -0.052 0 0.111 0 0 0
-
- 0.001
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
- true
- 1
- 0 0 0 0 0 0
-
-
-
-
- 0.0
- 0.01
-
-
-
-
- 0.0
- 0.01
-
-
-
-
-
-
- ~/out:=/gps/fix
-
-
-
-
-
-
-
- -0.064 0 0.121 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
-
- -0.052 0 0.111 0 0 0
-
-
- 0.0508
- 0.055
-
-
-
-
-
- -0.064 0 0.121 0 0 0
-
-
- model://turtlebot3_common/meshes/lds.dae
- 0.001 0.001 0.001
-
-
-
-
-
- true
- false
- -0.064 0 0.15 0 0 0
- 5
-
-
-
- 360
- 1.000000
- 0.000000
- 6.280000
-
-
-
- 0.00000
- 20.0
- 0.015000
-
-
- gaussian
- 0.0
- 0.01
-
-
-
-
-
- ~/out:=scan
-
- sensor_msgs/LaserScan
- base_scan
-
-
-
-
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 0.144 0.023 0 0 0
-
-
- model://turtlebot3_common/meshes/tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 -0.144 0.023 0 0 0
-
-
- model://turtlebot3_common/meshes/tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
- -0.177 -0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- -0.177 0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
-
- 0.069 -0.047 0.107 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.035
-
-
- 0 0.047 -0.005 0 0 0
-
-
- 0.008 0.130 0.022
-
-
-
-
- 0.069 -0.047 0.107 0 0 0
-
-
- 1
- 5
- 0.064 -0.047 0.107 0 0 0
-
-
-
-
-
- intel_realsense_r200_depth
- camera_depth_frame
- 0.07
- 0.001
- 5.0
-
-
-
-
-
- base_footprint
- base_link
- 0.0 0.0 0.010 0 0 0
-
-
-
- base_link
- imu_link
- -0.032 0 0.068 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- gps_link
- -0.05 0 0.05 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_left_link
- 0.0 0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_right_link
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- caster_back_right_link
-
-
-
- base_link
- caster_back_left_link
-
-
-
- base_link
- base_scan
- -0.064 0 0.121 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- camera_link
- 0.064 -0.065 0.094 0 0 0
-
- 0 0 1
-
-
-
-
-
-
-
-
- /tf:=tf
-
-
- 30
-
-
- wheel_left_joint
- wheel_right_joint
-
-
- 0.287
- 0.066
-
-
- 20
- 1.0
-
- cmd_vel
-
-
-
- true
- false
- false
-
- odom
- odom
- base_footprint
-
-
-
-
-
-
- ~/out:=joint_states
-
- 30
- wheel_left_joint
- wheel_right_joint
-
-
-
-
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/urdf/turtlebot3_waffle_gps.urdf b/nav2_gps_waypoint_follower_demo/urdf/turtlebot3_waffle_gps.urdf
deleted file mode 100644
index 8fa7b2c..0000000
--- a/nav2_gps_waypoint_follower_demo/urdf/turtlebot3_waffle_gps.urdf
+++ /dev/null
@@ -1,305 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/worlds/sonoma_raceway.world b/nav2_gps_waypoint_follower_demo/worlds/sonoma_raceway.world
deleted file mode 100644
index 9a08cbd..0000000
--- a/nav2_gps_waypoint_follower_demo/worlds/sonoma_raceway.world
+++ /dev/null
@@ -1,61 +0,0 @@
-
-
-
-
-
- 0.95 0.95 0.95 1
- 0.3 0.3 0.3 1
- true
-
-
- 3
-
-
-
-
- model://sun
-
-
- model://sonoma_raceway
- -287.5 143.5 -7 0 0 0
-
-
-
- EARTH_WGS84
- 38.161479
- -122.454630
- 488.0
- 180
-
-
-
- 100.0
- 0.01
- 1
-
-
- quick
- 150
- 0
- 1.400000
- 1
-
-
- 0.00001
- 0.2
- 2000.000000
- 0.01000
-
-
-
-
-
- model://turtlebot_waffle_gps
- 2 -2.5 0.3 0 0 0
-
-
-
-
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/worlds/tb3_sonoma_raceway.sdf.xacro b/nav2_gps_waypoint_follower_demo/worlds/tb3_sonoma_raceway.sdf.xacro
new file mode 100644
index 0000000..df1f6a0
--- /dev/null
+++ b/nav2_gps_waypoint_follower_demo/worlds/tb3_sonoma_raceway.sdf.xacro
@@ -0,0 +1,103 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ ogre2
+
+
+
+
+
+
+ EARTH_WGS84
+ ENU
+ 38.161479
+ -122.454630
+ 0
+ 0
+
+
+
+ 0
+ 0 0 10 0 0 0
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+ 1
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+ 10
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0
+
+
+
+ 0.003
+ 1
+
+
+
+
+ https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sonoma Raceway
+
+ sonoma_raceway
+ -287.5 143.5 -7 0 0 0
+
+
+
+