diff --git a/locker98_tools/locker98_tools/joy_teleop.py b/locker98_tools/locker98_tools/joy_teleop.py
index 7d0e038..e69b8c5 100755
--- a/locker98_tools/locker98_tools/joy_teleop.py
+++ b/locker98_tools/locker98_tools/joy_teleop.py
@@ -12,7 +12,7 @@ class JoyTeleopNode(Node):
def __init__(self, joystick):
super().__init__("joy_teleop")
self.joystick = joystick
- self.publisher_ = self.create_publisher(Twist, "/cmd_vel", 10)
+ self.publisher_ = self.create_publisher(Twist, "/a200_0651/cmd_vel", 10)
self.timer_ = self.create_timer(0.1, self.publish_news)
self.get_logger().info("Starting the robot news station")
@@ -21,7 +21,7 @@ class JoyTeleopNode(Node):
msg = Twist()
msg.linear.x = move*2
- msg.angular.z = r*2
+ msg.angular.z = -r*2
self.publisher_.publish(msg)
def get_joystick_right_stick(self):
diff --git a/locker98_tools_bringup/CMakeLists.txt b/locker98_tools_bringup/CMakeLists.txt
index 9b35e1b..28717dc 100644
--- a/locker98_tools_bringup/CMakeLists.txt
+++ b/locker98_tools_bringup/CMakeLists.txt
@@ -9,7 +9,7 @@ endif()
find_package(ament_cmake REQUIRED)
install(
- DIRECTORY launch rviz worlds
+ DIRECTORY launch worlds config
DESTINATION share/${PROJECT_NAME}/
)
diff --git a/locker98_tools_bringup/config/a200/localization.yaml b/locker98_tools_bringup/config/a200/localization.yaml
new file mode 100644
index 0000000..3a1556c
--- /dev/null
+++ b/locker98_tools_bringup/config/a200/localization.yaml
@@ -0,0 +1,55 @@
+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_skip_distance: 0.5
+ beam_skip_error_threshold: 0.9
+ beam_skip_threshold: 0.3
+ do_beamskip: false
+ global_frame_id: "map"
+ lambda_short: 0.1
+ laser_likelihood_max_dist: 2.0
+ laser_max_range: 100.0
+ laser_min_range: -1.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: "nav2_amcl::DifferentialMotionModel"
+ save_pose_rate: 0.5
+ sigma_hit: 0.2
+ 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
+ scan_topic: sensors/lidar3d_0/scan
+
+map_server:
+ ros__parameters:
+ use_sim_time: False
+ # Overridden in launch by the "map" launch configuration or provided default value.
+ # To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below.
+ yaml_filename: ""
+
+map_saver:
+ ros__parameters:
+ use_sim_time: False
+ save_map_timeout: 5.0
+ free_thresh_default: 0.25
+ occupied_thresh_default: 0.65
+ map_subscribe_transient_local: True
diff --git a/locker98_tools_bringup/config/a200/nav2.yaml b/locker98_tools_bringup/config/a200/nav2.yaml
new file mode 100644
index 0000000..2e8de2f
--- /dev/null
+++ b/locker98_tools_bringup/config/a200/nav2.yaml
@@ -0,0 +1,293 @@
+
+bt_navigator:
+ ros__parameters:
+ use_sim_time: True
+ global_frame: map
+ robot_base_frame: base_link
+ odom_topic: platform/odom/filtered
+ bt_loop_duration: 10
+ default_server_timeout: 20
+ # '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_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
+
+bt_navigator_navigate_through_poses_rclcpp_node:
+ ros__parameters:
+ use_sim_time: True
+
+bt_navigator_navigate_to_pose_rclcpp_node:
+ ros__parameters:
+ use_sim_time: True
+
+controller_server:
+ ros__parameters:
+ use_sim_time: True
+ 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"] # "precise_goal_checker"
+ controller_plugins: ["FollowPath"]
+
+ # Progress checker parameters
+ progress_checker:
+ plugin: "nav2_controller::SimpleProgressChecker"
+ required_movement_radius: 0.5
+ movement_time_allowance: 10.0
+ # Goal checker parameters
+ #precise_goal_checker:
+ # plugin: "nav2_controller::SimpleGoalChecker"
+ # xy_goal_tolerance: 0.25
+ # yaw_goal_tolerance: 0.25
+ # stateful: True
+ general_goal_checker:
+ stateful: True
+ plugin: "nav2_controller::SimpleGoalChecker"
+ xy_goal_tolerance: 0.3
+ yaw_goal_tolerance: 0.3
+ # DWB parameters
+ FollowPath:
+ plugin: "dwb_core::DWBLocalPlanner"
+ debug_trajectory_details: True
+ min_vel_x: 0.0
+ min_vel_y: 0.0
+ max_vel_x: 1.0
+ max_vel_y: 0.0
+ max_vel_theta: 1.0
+ min_speed_xy: 0.0
+ max_speed_xy: 1.0
+ 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: 0.5
+ acc_lim_y: 0.0
+ acc_lim_theta: 0.5
+ decel_lim_x: -0.5
+ decel_lim_y: 0.0
+ decel_lim_theta: -0.5
+ 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: 12.0
+ RotateToGoal.lookahead_time: -1.0
+
+local_costmap:
+ local_costmap:
+ ros__parameters:
+ update_frequency: 5.0
+ publish_frequency: 2.0
+ global_frame: odom
+ robot_base_frame: base_link
+ use_sim_time: True
+ rolling_window: true
+ width: 5
+ height: 5
+ resolution: 0.06
+ footprint: "[ [0.55, 0.45], [0.55, -0.45], [-0.55, -0.45], [-0.55, 0.45] ]"
+ plugins: ["static_layer", "voxel_layer", "inflation_layer"]
+ inflation_layer:
+ plugin: "nav2_costmap_2d::InflationLayer"
+ cost_scaling_factor: 4.0
+ inflation_radius: 0.8
+ voxel_layer:
+ plugin: "nav2_costmap_2d::VoxelLayer"
+ enabled: True
+ publish_voxel_map: True
+ origin_z: 0.0
+ z_resolution: 0.05
+ z_voxels: 16
+ max_obstacle_height: 2.0
+ mark_threshold: 0
+ observation_sources: scan
+ scan:
+ topic: sensors/lidar3d_0/scan
+ max_obstacle_height: 2.0
+ clearing: True
+ marking: True
+ data_type: "LaserScan"
+ raytrace_max_range: 3.0
+ raytrace_min_range: 0.0
+ obstacle_max_range: 2.5
+ obstacle_min_range: 0.0
+ static_layer:
+ plugin: "nav2_costmap_2d::StaticLayer"
+ map_subscribe_transient_local: True
+ always_send_full_costmap: True
+
+global_costmap:
+ global_costmap:
+ ros__parameters:
+ update_frequency: 1.0
+ publish_frequency: 1.0
+ global_frame: map
+ robot_base_frame: base_link
+ use_sim_time: True
+ footprint: "[ [0.55, 0.45], [0.55, -0.45], [-0.55, -0.45], [-0.55, 0.45] ]"
+ resolution: 0.06
+ track_unknown_space: true
+ plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
+ obstacle_layer:
+ plugin: "nav2_costmap_2d::ObstacleLayer"
+ enabled: True
+ observation_sources: scan
+ scan:
+ topic: sensors/lidar3d_0/scan
+ max_obstacle_height: 2.0
+ clearing: True
+ marking: True
+ data_type: "LaserScan"
+ raytrace_max_range: 3.0
+ raytrace_min_range: 0.0
+ obstacle_max_range: 2.5
+ obstacle_min_range: 0.0
+ static_layer:
+ plugin: "nav2_costmap_2d::StaticLayer"
+ map_subscribe_transient_local: True
+ inflation_layer:
+ plugin: "nav2_costmap_2d::InflationLayer"
+ cost_scaling_factor: 4.0
+ inflation_radius: 0.8
+ always_send_full_costmap: True
+
+planner_server:
+ ros__parameters:
+ expected_planner_frequency: 20.0
+ use_sim_time: True
+ planner_plugins: ["GridBased"]
+ GridBased:
+ plugin: "nav2_navfn_planner/NavfnPlanner"
+ tolerance: 0.5
+ use_astar: false
+ allow_unknown: true
+
+smoother_server:
+ ros__parameters:
+ use_sim_time: True
+ smoother_plugins: ["simple_smoother"]
+ simple_smoother:
+ plugin: "nav2_smoother::SimpleSmoother"
+ tolerance: 1.0e-10
+ max_its: 1000
+ do_refinement: True
+
+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"
+ wait:
+ plugin: "nav2_behaviors/Wait"
+ assisted_teleop:
+ plugin: "nav2_behaviors/AssistedTeleop"
+ global_frame: odom
+ robot_base_frame: base_link
+ transform_tolerance: 0.1
+ use_sim_time: true
+ simulate_ahead_time: 2.0
+ max_rotational_vel: 1.0
+ min_rotational_vel: 0.2
+ rotational_acc_lim: 0.5
+
+robot_state_publisher:
+ ros__parameters:
+ use_sim_time: True
+
+waypoint_follower:
+ ros__parameters:
+ use_sim_time: True
+ loop_rate: 20
+ stop_on_failure: false
+ waypoint_task_executor_plugin: "wait_at_waypoint"
+ wait_at_waypoint:
+ plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+ enabled: True
+ waypoint_pause_duration: 200
+
+velocity_smoother:
+ ros__parameters:
+ use_sim_time: True
+ smoothing_frequency: 20.0
+ scale_velocities: False
+ feedback: "OPEN_LOOP"
+ max_velocity: [1.0, 0.0, 1.0]
+ min_velocity: [-1.0, 0.0, -1.0]
+ max_accel: [0.5, 0.0, 0.5]
+ max_decel: [-0.5, 0.0, -0.5]
+ odom_topic: "platform/odom/filtered"
+ odom_duration: 0.1
+ deadband_velocity: [0.0, 0.0, 0.0]
+ velocity_timeout: 1.0
diff --git a/locker98_tools_bringup/config/a200/slam.yaml b/locker98_tools_bringup/config/a200/slam.yaml
new file mode 100644
index 0000000..8f36dba
--- /dev/null
+++ b/locker98_tools_bringup/config/a200/slam.yaml
@@ -0,0 +1,75 @@
+slam_toolbox:
+ ros__parameters:
+
+ # Plugin params
+ 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
+ ceres_loss_function: None
+
+ # ROS Parameters
+ odom_frame: odom
+ map_frame: map
+ base_frame: base_footprint
+ scan_topic: sensors/lidar3d_0/scan
+ use_map_saver: true
+ mode: mapping #localization
+
+ # if you'd like to immediately start continuing a map at a given pose
+ # or at the dock, but they are mutually exclusive, if pose is given
+ # will use pose
+ #map_file_name: test_steve
+ # map_start_pose: [0.0, 0.0, 0.0]
+ #map_start_at_dock: true
+
+ debug_logging: true
+ throttle_scans: 1
+ transform_publish_period: 0.02 #if 0 never publishes odometry
+ map_update_interval: 5.0
+ resolution: 0.05
+ min_laser_range: 0.0 #for rastering images
+ max_laser_range: 20.0 #for rastering images
+ minimum_time_interval: 0.5
+ transform_timeout: 0.2
+ tf_buffer_duration: 30.0
+ stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
+ enable_interactive_mode: true
+
+ # General Parameters
+ use_scan_matching: true
+ use_scan_barycenter: true
+ minimum_travel_distance: 0.5
+ minimum_travel_heading: 0.5
+ scan_buffer_size: 10
+ scan_buffer_maximum_scan_distance: 10.0
+ link_match_minimum_response_fine: 0.1
+ link_scan_maximum_distance: 1.5
+ loop_search_maximum_distance: 3.0
+ do_loop_closing: true
+ loop_match_minimum_chain_size: 10
+ loop_match_maximum_variance_coarse: 3.0
+ loop_match_minimum_response_coarse: 0.35
+ loop_match_minimum_response_fine: 0.45
+
+ # Correlation Parameters - Correlation Parameters
+ correlation_search_space_dimension: 0.5
+ correlation_search_space_resolution: 0.01
+ correlation_search_space_smear_deviation: 0.1
+
+ # Correlation Parameters - Loop Closure Parameters
+ loop_search_space_dimension: 8.0
+ loop_search_space_resolution: 0.05
+ loop_search_space_smear_deviation: 0.03
+
+ # Scan Matcher Parameters
+ distance_variance_penalty: 0.5
+ angle_variance_penalty: 1.0
+
+ fine_search_angle_offset: 0.00349
+ coarse_search_angle_offset: 0.349
+ coarse_angle_resolution: 0.0349
+ minimum_angle_penalty: 0.9
+ minimum_distance_penalty: 0.5
+ use_response_expansion: true
diff --git a/locker98_tools_bringup/rviz/nav2_config.rviz b/locker98_tools_bringup/config/rviz/nav2_config.rviz
similarity index 100%
rename from locker98_tools_bringup/rviz/nav2_config.rviz
rename to locker98_tools_bringup/config/rviz/nav2_config.rviz
diff --git a/locker98_tools_bringup/rviz/slam_config.rviz b/locker98_tools_bringup/config/rviz/slam_config.rviz
similarity index 100%
rename from locker98_tools_bringup/rviz/slam_config.rviz
rename to locker98_tools_bringup/config/rviz/slam_config.rviz
diff --git a/locker98_tools_bringup/launch/husky.localization.launch.py b/locker98_tools_bringup/launch/husky.localization.launch.py
new file mode 100644
index 0000000..07d8ed2
--- /dev/null
+++ b/locker98_tools_bringup/launch/husky.localization.launch.py
@@ -0,0 +1,88 @@
+from ament_index_python.packages import get_package_share_directory
+import os
+from clearpath_config.common.utils.yaml import read_yaml
+from clearpath_config.clearpath_config import ClearpathConfig
+
+from launch import LaunchDescription
+from launch.actions import (
+ DeclareLaunchArgument,
+ GroupAction,
+ IncludeLaunchDescription,
+ OpaqueFunction
+)
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+
+from launch.substitutions import (
+ LaunchConfiguration,
+ PathJoinSubstitution
+)
+
+from launch_ros.actions import PushRosNamespace
+
+
+ARGUMENTS = [
+ DeclareLaunchArgument('use_sim_time', default_value='false',
+ choices=['true', 'false'],
+ description='Use sim time'),
+ DeclareLaunchArgument('setup_path',
+ default_value='/etc/clearpath/',
+ description='Clearpath setup path')
+]
+
+
+def launch_setup(context, *args, **kwargs):
+ # Packages
+ pkg_nav2_bringup = get_package_share_directory('nav2_bringup')
+ package_config_path = get_package_share_directory('locker98_tools_bringup')
+
+ # Launch Configurations
+ use_sim_time = LaunchConfiguration('use_sim_time')
+ setup_path = LaunchConfiguration('setup_path')
+ map = LaunchConfiguration('map')
+
+ # Read robot YAML
+ config = read_yaml(setup_path.perform(context) + 'robot.yaml')
+ # Parse robot YAML into config
+ clearpath_config = ClearpathConfig(config)
+
+ namespace = clearpath_config.system.namespace
+ platform_model = clearpath_config.platform.get_platform_model()
+
+ file_parameters = os.path.join(
+ package_config_path,
+ 'config',
+ platform_model,
+ 'localization.yaml'
+ )
+
+
+
+ launch_localization = PathJoinSubstitution(
+ [pkg_nav2_bringup, 'launch', 'localization_launch.py'])
+
+ localization = GroupAction([
+ PushRosNamespace(namespace),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(launch_localization),
+ launch_arguments=[
+ ('namespace', namespace),
+ ('map', map),
+ ('use_sim_time', use_sim_time),
+ ('params_file', file_parameters)
+ ]
+ ),
+ ])
+
+ return [localization]
+
+
+def generate_launch_description():
+ map_arg = DeclareLaunchArgument(
+ 'map',
+ description='Full path to map yaml file to load')
+
+ ld = LaunchDescription(ARGUMENTS)
+ ld.add_action(map_arg)
+ ld.add_action(OpaqueFunction(function=launch_setup))
+ return ld
\ No newline at end of file
diff --git a/locker98_tools_bringup/launch/husky.nav2.launch.py b/locker98_tools_bringup/launch/husky.nav2.launch.py
new file mode 100644
index 0000000..4d44485
--- /dev/null
+++ b/locker98_tools_bringup/launch/husky.nav2.launch.py
@@ -0,0 +1,86 @@
+from ament_index_python.packages import get_package_share_directory
+import os
+from clearpath_config.common.utils.yaml import read_yaml
+from clearpath_config.clearpath_config import ClearpathConfig
+
+from launch import LaunchDescription
+from launch.actions import (
+ DeclareLaunchArgument,
+ GroupAction,
+ IncludeLaunchDescription,
+ OpaqueFunction
+)
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+
+from launch.substitutions import (
+ LaunchConfiguration,
+ PathJoinSubstitution
+)
+
+from launch_ros.actions import PushRosNamespace, SetRemap
+
+
+ARGUMENTS = [
+ DeclareLaunchArgument('use_sim_time', default_value='false',
+ choices=['true', 'false'],
+ description='Use sim time'),
+ DeclareLaunchArgument('setup_path',
+ default_value='/etc/clearpath/',
+ description='Clearpath setup path')
+]
+
+
+def launch_setup(context, *args, **kwargs):
+ # Packages
+ pkg_nav2_bringup = get_package_share_directory('nav2_bringup')
+ package_config_path = get_package_share_directory('locker98_tools_bringup')
+
+ # Launch Configurations
+ use_sim_time = LaunchConfiguration('use_sim_time')
+ setup_path = LaunchConfiguration('setup_path')
+
+ # Read robot YAML
+ config = read_yaml(setup_path.perform(context) + 'robot.yaml')
+ # Parse robot YAML into config
+ clearpath_config = ClearpathConfig(config)
+
+ namespace = clearpath_config.system.namespace
+ platform_model = clearpath_config.platform.get_platform_model()
+
+ file_parameters = os.path.join(
+ package_config_path,
+ 'config',
+ platform_model,
+ 'nav2.yaml'
+ )
+
+
+
+ launch_nav2 = PathJoinSubstitution(
+ [pkg_nav2_bringup, 'launch', 'navigation_launch.py'])
+
+ nav2 = GroupAction([
+ PushRosNamespace(namespace),
+ SetRemap('/' + namespace + '/global_costmap/sensors/lidar3d_0/scan',
+ '/' + namespace + '/sensors/lidar3d_0/scan'),
+ SetRemap('/' + namespace + '/local_costmap/sensors/lidar3d_0/scan',
+ '/' + namespace + '/sensors/lidar3d_0/scan'),
+
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(launch_nav2),
+ launch_arguments=[
+ ('use_sim_time', use_sim_time),
+ ('params_file', file_parameters),
+ ('use_composition', 'False'),
+ ('namespace', namespace)
+ ]
+ ),
+ ])
+
+ return [nav2]
+
+
+def generate_launch_description():
+ ld = LaunchDescription(ARGUMENTS)
+ ld.add_action(OpaqueFunction(function=launch_setup))
+ return ld
\ No newline at end of file
diff --git a/locker98_tools_bringup/launch/husky.slam.launch.py b/locker98_tools_bringup/launch/husky.slam.launch.py
new file mode 100644
index 0000000..39f4f23
--- /dev/null
+++ b/locker98_tools_bringup/launch/husky.slam.launch.py
@@ -0,0 +1,89 @@
+from ament_index_python.packages import get_package_share_directory
+import os
+from clearpath_config.common.utils.yaml import read_yaml
+from clearpath_config.clearpath_config import ClearpathConfig
+
+from launch import LaunchDescription
+from launch.actions import (
+ DeclareLaunchArgument,
+ OpaqueFunction
+)
+
+from launch.substitutions import (
+ LaunchConfiguration,
+ PathJoinSubstitution
+)
+
+from launch_ros.actions import Node
+
+from nav2_common.launch import RewrittenYaml
+
+
+ARGUMENTS = [
+ DeclareLaunchArgument('use_sim_time', default_value='false',
+ choices=['true', 'false'],
+ description='Use sim time'),
+ DeclareLaunchArgument('setup_path',
+ default_value='/etc/clearpath/',
+ description='Clearpath setup path')
+]
+
+
+def launch_setup(context, *args, **kwargs):
+ # Packages
+ package_config_path = get_package_share_directory('locker98_tools_bringup')
+
+ # Launch Configurations
+ use_sim_time = LaunchConfiguration('use_sim_time')
+ setup_path = LaunchConfiguration('setup_path')
+
+ # Read robot YAML
+ config = read_yaml(setup_path.perform(context) + 'robot.yaml')
+ # Parse robot YAML into config
+ clearpath_config = ClearpathConfig(config)
+
+ namespace = clearpath_config.system.namespace
+ platform_model = clearpath_config.platform.get_platform_model()
+
+ file_parameters = os.path.join(
+ package_config_path,
+ 'config',
+ platform_model,
+ 'slam.yaml'
+ )
+
+
+
+ rewritten_parameters = RewrittenYaml(
+ source_file=file_parameters,
+ root_key=namespace,
+ param_rewrites={},
+ convert_types=True
+ )
+
+ slam = Node(
+ package='slam_toolbox',
+ executable='async_slam_toolbox_node',
+ name='slam_toolbox',
+ namespace=namespace,
+ output='screen',
+ parameters=[
+ rewritten_parameters,
+ {'use_sim_time': use_sim_time}
+ ],
+ remappings=[
+ ('/tf', 'tf'),
+ ('/tf_static', 'tf_static'),
+ ('/scan', 'sensors/lidar3d_0/scan'),
+ ('/map', 'map'),
+ ('/map_metadata', 'map_metadata'),
+ ]
+ )
+
+ return [slam]
+
+
+def generate_launch_description():
+ ld = LaunchDescription(ARGUMENTS)
+ ld.add_action(OpaqueFunction(function=launch_setup))
+ return ld
\ No newline at end of file
diff --git a/locker98_tools_bringup/launch/nav2.launch.py b/locker98_tools_bringup/launch/nav2.launch.py
index c3f76b1..b8906b1 100644
--- a/locker98_tools_bringup/launch/nav2.launch.py
+++ b/locker98_tools_bringup/launch/nav2.launch.py
@@ -15,7 +15,7 @@ def generate_launch_description():
# Define RViz config path
rviz_config_path = os.path.join(
get_package_share_directory('locker98_tools_bringup'),
- 'rviz', 'nav2_config.rviz'
+ 'config', 'rviz', 'nav2_config.rviz'
)
# Include the bringup launch file
diff --git a/locker98_tools_bringup/launch/nav2.launch.xml b/locker98_tools_bringup/launch/nav2.launch.xml
index 18df91e..17bac80 100644
--- a/locker98_tools_bringup/launch/nav2.launch.xml
+++ b/locker98_tools_bringup/launch/nav2.launch.xml
@@ -11,6 +11,6 @@
-
+
\ No newline at end of file
diff --git a/locker98_tools_bringup/launch/slam.launch.py b/locker98_tools_bringup/launch/slam.launch.py
index 5e2b8f2..0b48a7d 100644
--- a/locker98_tools_bringup/launch/slam.launch.py
+++ b/locker98_tools_bringup/launch/slam.launch.py
@@ -37,7 +37,7 @@ def generate_launch_description():
executable='rviz2',
output='screen',
arguments=[
- '-d', os.path.join(locker98_tools_bringup_dir, 'rviz', 'slam_config.rviz')
+ '-d', os.path.join(locker98_tools_bringup_dir, 'config', 'rviz', 'slam_config.rviz')
]
)
diff --git a/locker98_tools_bringup/launch/slam.launch.xml b/locker98_tools_bringup/launch/slam.launch.xml
index 625fdf6..1d35bae 100644
--- a/locker98_tools_bringup/launch/slam.launch.xml
+++ b/locker98_tools_bringup/launch/slam.launch.xml
@@ -10,6 +10,6 @@
-
+
\ No newline at end of file