diff --git a/config/mapper_params_online_async.yaml b/config/mapper_params_online_async.yaml index a43d54b..b35bd13 100644 --- a/config/mapper_params_online_async.yaml +++ b/config/mapper_params_online_async.yaml @@ -12,8 +12,9 @@ slam_toolbox: # ROS Parameters odom_frame: odom map_frame: map + map_topic: map #tryout? base_frame: base_footprint - scan_topic: /scan + scan_topic: scan mode: localization # if you'd like to immediately start continuing a map at a given pose diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 4ee2bd3..615ed94 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -207,7 +207,7 @@ local_costmap: mark_threshold: 0 observation_sources: scan scan: - topic: /scan + topic: scan max_obstacle_height: 2.0 clearing: True marking: True @@ -238,7 +238,7 @@ global_costmap: enabled: True observation_sources: scan scan: - topic: /scan + topic: scan max_obstacle_height: 2.0 clearing: True marking: True diff --git a/launch/robot_controller.launch.py b/launch/robot_controller.launch.py index 73de7f7..4c08f7a 100755 --- a/launch/robot_controller.launch.py +++ b/launch/robot_controller.launch.py @@ -10,7 +10,7 @@ def generate_launch_description(): package='segwayrmp', executable='SmartCar', name='SmartCar', - remappings=[('/cmd_vel','/cmd_vel_out')], + remappings=[('cmd_vel','cmd_vel_out'), ('/odom','odom'), ('/imu','imu'), ('/bms_fb','bms_fb'), ('/joint_states','joint_states')], namespace = "/rmp" ) diff --git a/launch/robot_joystick.launch.py b/launch/robot_joystick.launch.py index 1ab7b65..279ed47 100644 --- a/launch/robot_joystick.launch.py +++ b/launch/robot_joystick.launch.py @@ -26,7 +26,7 @@ def generate_launch_description(): executable='rmp220_teleop', name='rmp220_teleop', parameters=[joy_params, {'use_sim_time': use_sim_time}], - remappings=[('/cmd_vel','/cmd_vel_joy')], + remappings=[('cmd_vel','cmd_vel_joy')], namespace = "/rmp" )