Browse Source

在启动amcl_ydlidar_x2l.launch进行自动导航时,先启动robot_bringup.launch

corvin rasp melodic 2 years ago
parent
commit
0d4573ea75

+ 19 - 19
src/robot_navigation/launch/amcl_teb.launch

@@ -1,31 +1,31 @@
 <launch>
-        <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
-        
-        <!--  ****** Maps *****  -->
+    <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
+
+    <!--  ****** Maps *****  -->
 	<node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/test_map.yaml" output="screen" />
 
-        <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
+    <include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
 
-        <!--  ************** Navigation ***************  -->
+    <!--  ************** Navigation ***************  -->
 	<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
-  	  	<rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="global_costmap" />
-  	 	<rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="local_costmap" />
-  		<rosparam file="$(find robot_navigation)/config/teb_cfg/local_costmap_params.yaml" command="load" />
-  		<rosparam file="$(find robot_navigation)/config/teb_cfg/global_costmap_params.yaml" command="load" />
-  		<rosparam file="$(find robot_navigation)/config/teb_cfg/teb_local_planner_params.yaml" command="load" />
-                <rosparam file="$(find robot_navigation)/config/teb_cfg/base_global_planner_params.yaml" command="load" />
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="global_costmap" />
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/costmap_common_params.yaml" command="load" ns="local_costmap" />
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/local_costmap_params.yaml" command="load" />
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/global_costmap_params.yaml" command="load" />
+  	  <rosparam file="$(find robot_navigation)/config/teb_cfg/teb_local_planner_params.yaml" command="load" />
+      <rosparam file="$(find robot_navigation)/config/teb_cfg/base_global_planner_params.yaml" command="load" />
 
-		<param name="base_global_planner" value="global_planner/GlobalPlanner" />
-		<param name="planner_frequency" value="1.0" />
-		<param name="planner_patience" value="5.0" />
+	  <param name="base_global_planner" value="global_planner/GlobalPlanner" />
+	  <param name="planner_frequency" value="1.0" />
+	  <param name="planner_patience" value="5.0" />
 
-		<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
-		<param name="controller_frequency" value="15.0" />
-		<param name="controller_patience" value="15.0" />
+	  <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
+	  <param name="controller_frequency" value="15.0" />
+	  <param name="controller_patience" value="15.0" />
 	</node>
 
 	<node pkg="amcl" type="amcl" name="amcl" output="screen">
-		<rosparam file="$(find robot_navigation)/config/teb_cfg/amcl_params.yaml" command="load" />
+	    <rosparam file="$(find robot_navigation)/config/teb_cfg/amcl_params.yaml" command="load" />
 	</node>
-
 </launch>
+

+ 5 - 1
src/robot_navigation/launch/amcl_ydlidar_X2L.launch

@@ -2,10 +2,14 @@
   Description:使用EAI的X2L雷达进行amcl定位,加载地图进行路径规划,自动导航
   Author: corvin
   History:
-    20200326: init this file.
+    20200326:init this file.
     20200804:将odom_mode_type改为omni-corrected,对应odom_alpha参数也更新.
+    20220810:在启动amcl算法进行自动导航时,先将robot_bringup.launch启动.
 -->
 <launch>
+  <!-- startup robot bringup -->
+  <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
+
   <!-- Run the map server with a map -->
   <node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/test_map.yaml" />
 

+ 0 - 20
src/robot_navigation/launch/gazebo.launch

@@ -1,20 +0,0 @@
-<launch>
-  <include
-    file="$(find gazebo_ros)/launch/empty_world.launch" />
-  <node
-    name="tf_footprint_base"
-    pkg="tf"
-    type="static_transform_publisher"
-    args="0 0 0 0 0 0 base_link base_footprint 40" />
-  <node
-    name="spawn_model"
-    pkg="gazebo_ros"
-    type="spawn_model"
-    args="-file $(find carebot_description)/urdf/carebot.urdf -urdf -model carebot"
-    output="screen" />
-  <node
-    name="fake_joint_calibration"
-    pkg="rostopic"
-    type="rostopic"
-    args="pub /calibrated std_msgs/Bool true" />
-</launch>

File diff suppressed because it is too large
+ 0 - 4
src/robot_navigation/maps/mymap.pgm


+ 0 - 7
src/robot_navigation/maps/mymap.yaml

@@ -1,7 +0,0 @@
-image: mymap.pgm
-resolution: 0.050000
-origin: [-16.200000, -5.000000, 0.000000]
-negate: 0
-occupied_thresh: 0.65
-free_thresh: 0.196
-

File diff suppressed because it is too large
+ 1 - 1
src/robot_navigation/maps/test_map.pgm


+ 1 - 1
src/robot_navigation/maps/test_map.yaml

@@ -1,6 +1,6 @@
 image: test_map.pgm
 resolution: 0.050000
-origin: [-16.200000, -16.200000, 0.000000]
+origin: [-5.000000, -5.000000, 0.000000]
 negate: 0
 occupied_thresh: 0.65
 free_thresh: 0.196

+ 0 - 367
src/robot_navigation/rviz/blind_nav.rviz

@@ -1,367 +0,0 @@
-Panels:
-  - Class: rviz/Displays
-    Help Height: 78
-    Name: Displays
-    Property Tree Widget:
-      Expanded:
-        - /TF1/Frames1
-        - /TF1/Tree1
-        - /Global Map1/Map1
-        - /Bumper/cliff PointCloud1/Status1
-      Splitter Ratio: 0.5
-    Tree Height: 769
-  - Class: rviz/Selection
-    Name: Selection
-  - Class: rviz/Tool Properties
-    Expanded:
-      - /2D Pose Estimate1
-      - /2D Nav Goal1
-    Name: Tool Properties
-    Splitter Ratio: 0.588679
-  - Class: rviz/Views
-    Expanded:
-      - /Current View1
-    Name: Views
-    Splitter Ratio: 0.5
-  - Class: rviz/Time
-    Experimental: false
-    Name: Time
-    SyncMode: 0
-    SyncSource: ""
-Visualization Manager:
-  Class: ""
-  Displays:
-    - Alpha: 0.5
-      Cell Size: 1
-      Class: rviz/Grid
-      Color: 160; 160; 164
-      Enabled: true
-      Line Style:
-        Line Width: 0.03
-        Value: Lines
-      Name: Grid
-      Normal Cell Count: 0
-      Offset:
-        X: 0
-        Y: 0
-        Z: 0
-      Plane: XY
-      Plane Cell Count: 10
-      Reference Frame: <Fixed Frame>
-      Value: true
-    - Alpha: 1
-      Class: rviz/RobotModel
-      Collision Enabled: false
-      Enabled: true
-      Links:
-        All Links Enabled: true
-        Expand Joint Details: false
-        Expand Link Details: false
-        Expand Tree: false
-        Link Tree Style: Links in Alphabetic Order
-        base_footprint:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        base_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        camera_depth_frame:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        camera_depth_optical_frame:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        camera_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        camera_rgb_frame:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        camera_rgb_optical_frame:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        caster_back_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        caster_front_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        cliff_sensor_front_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        cliff_sensor_left_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        cliff_sensor_right_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        gyro_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-        plate_bottom_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        plate_middle_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        plate_top_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_bottom_0_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_bottom_1_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_bottom_2_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_bottom_3_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_bottom_4_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_bottom_5_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_kinect_0_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_kinect_1_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_middle_0_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_middle_1_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_middle_2_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_middle_3_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_top_0_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_top_1_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_top_2_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        pole_top_3_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        wheel_left_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        wheel_right_link:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-      Name: RobotModel
-      Robot Description: robot_description
-      TF Prefix: ""
-      Update Interval: 0
-      Value: true
-      Visual Enabled: true
-    - Class: rviz/TF
-      Enabled: false
-      Frame Timeout: 15
-      Frames:
-        All Enabled: false
-      Marker Scale: 1
-      Name: TF
-      Show Arrows: true
-      Show Axes: true
-      Show Names: false
-      Tree:
-        {}
-      Update Interval: 0
-      Value: false
-    - Class: rviz/Group
-      Displays:
-        - Alpha: 0.7
-          Class: rviz/Map
-          Color Scheme: costmap
-          Draw Behind: false
-          Enabled: true
-          Name: Costmap
-          Topic: /move_base/local_costmap/costmap
-          Value: true
-        - Alpha: 1
-          Buffer Length: 1
-          Class: rviz/Path
-          Color: 0; 12; 255
-          Enabled: true
-          Name: Planner
-          Topic: /move_base/TrajectoryPlannerROS/local_plan
-          Value: true
-      Enabled: true
-      Name: Local Map
-    - Class: rviz/Group
-      Displays:
-        - Alpha: 0.4
-          Class: rviz/Map
-          Color Scheme: costmap
-          Draw Behind: true
-          Enabled: true
-          Name: Map
-          Topic: /move_base/global_costmap/costmap
-          Value: true
-        - Alpha: 1
-          Buffer Length: 1
-          Class: rviz/Path
-          Color: 255; 0; 0
-          Enabled: true
-          Name: Planner
-          Topic: /move_base/TrajectoryPlannerROS/global_plan
-          Value: true
-      Enabled: true
-      Name: Global Map
-    - Alpha: 1
-      Autocompute Intensity Bounds: true
-      Autocompute Value Bounds:
-        Max Value: 10
-        Min Value: -10
-        Value: true
-      Axis: Z
-      Channel Name: intensity
-      Class: rviz/PointCloud2
-      Color: 255; 255; 255
-      Color Transformer: ""
-      Decay Time: 0
-      Enabled: true
-      Max Color: 255; 255; 255
-      Max Intensity: 4096
-      Min Color: 0; 0; 0
-      Min Intensity: 0
-      Name: Bumper/cliff PointCloud
-      Position Transformer: ""
-      Queue Size: 10
-      Selectable: true
-      Size (Pixels): 3
-      Size (m): 0.05
-      Style: Spheres
-      Topic: /mobile_base/sensors/bumper_pointcloud
-      Use Fixed Frame: true
-      Use rainbow: false
-      Value: true
-    - Alpha: 1
-      Class: rviz/Polygon
-      Color: 25; 255; 0
-      Enabled: true
-      Name: Polygon
-      Topic: /move_base/local_costmap/footprint_layer/footprint_stamped
-      Value: true
-  Enabled: true
-  Global Options:
-    Background Color: 48; 48; 48
-    Fixed Frame: odom
-    Frame Rate: 30
-  Name: root
-  Tools:
-    - Class: rviz/MoveCamera
-    - Class: rviz/Interact
-      Hide Inactive Objects: true
-    - Class: rviz/Select
-    - Class: rviz/SetInitialPose
-      Topic: /initialpose
-    - Class: rviz/SetGoal
-      Topic: /move_base_simple/goal
-    - Class: rviz/Measure
-  Value: true
-  Views:
-    Current:
-      Class: rviz/Orbit
-      Distance: 10.0367
-      Focal Point:
-        X: 0.644818
-        Y: 3.7827
-        Z: -0.57592
-      Name: Current View
-      Near Clip Distance: 0.01
-      Pitch: 1.4398
-      Target Frame: <Fixed Frame>
-      Value: Orbit (rviz)
-      Yaw: 2.99003
-    Saved: ~
-Window Geometry:
-  Displays:
-    collapsed: false
-  Height: 985
-  Hide Left Dock: false
-  Hide Right Dock: false
-  QMainWindow State: 000000ff00000000fd0000000400000000000003600000038bfc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006901000005fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000320000038b000000d701000005000000010000010b0000038bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000320000038b000000a901000005fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000024c01000005fb0000000800540069006d006501000000000000045000000000000000000000030f0000038b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
-  Selection:
-    collapsed: false
-  Time:
-    collapsed: false
-  Tool Properties:
-    collapsed: false
-  Views:
-    collapsed: false
-  Width: 1920
-  X: 0
-  Y: 40

+ 0 - 5
src/robot_navigation/rviz/readme.txt

@@ -1,5 +0,0 @@
-
-===== Filename Extensions =====
-
- * .vcg  : fuerte
- * .rviz : groovy

+ 127 - 48
src/robot_navigation/rviz/view_navigation.rviz

@@ -5,8 +5,8 @@ Panels:
     Property Tree Widget:
       Expanded:
         - /Odometry1/Shape1
-      Splitter Ratio: 0.486111104
-    Tree Height: 314
+      Splitter Ratio: 0.5083333253860474
+    Tree Height: 398
   - Class: rviz/Selection
     Name: Selection
   - Class: rviz/Tool Properties
@@ -15,7 +15,7 @@ Panels:
       - /2D Nav Goal1
       - /Publish Point1
     Name: Tool Properties
-    Splitter Ratio: 0.588679016
+    Splitter Ratio: 0.5886790156364441
   - Class: rviz/Views
     Expanded:
       - /Current View1
@@ -26,18 +26,20 @@ Panels:
     Name: Time
     SyncMode: 0
     SyncSource: LaserScan
+Preferences:
+  PromptSaveOnExit: true
 Toolbars:
   toolButtonStyle: 2
 Visualization Manager:
   Class: ""
   Displays:
-    - Alpha: 0.699999988
+    - Alpha: 0.699999988079071
       Cell Size: 1
       Class: rviz/Grid
       Color: 50; 115; 54
       Enabled: true
       Line Style:
-        Line Width: 0.0299999993
+        Line Width: 0.029999999329447746
         Value: Lines
       Name: Grid
       Normal Cell Count: 0
@@ -54,19 +56,31 @@ Visualization Manager:
       Frame Timeout: 15
       Frames:
         All Enabled: true
+        back_wheel_link:
+          Value: true
         base_footprint:
           Value: true
         base_imu_link:
           Value: true
         base_link:
           Value: true
+        front_wheel_link:
+          Value: true
+        left_wheel_link:
+          Value: true
         lidar:
           Value: true
         map:
           Value: true
         odom_combined:
           Value: true
-      Marker Scale: 0.600000024
+        right_wheel_link:
+          Value: true
+        servo_left_right_link:
+          Value: true
+        servo_up_down_link:
+          Value: true
+      Marker Scale: 0.6000000238418579
       Name: TF
       Show Arrows: true
       Show Axes: true
@@ -76,13 +90,24 @@ Visualization Manager:
           odom_combined:
             base_footprint:
               base_link:
+                back_wheel_link:
+                  {}
                 base_imu_link:
                   {}
+                front_wheel_link:
+                  {}
+                left_wheel_link:
+                  {}
                 lidar:
                   {}
+                right_wheel_link:
+                  {}
+                servo_left_right_link:
+                  servo_up_down_link:
+                    {}
       Update Interval: 0
       Value: true
-    - Alpha: 0.800000012
+    - Alpha: 0.800000011920929
       Class: rviz/Map
       Color Scheme: map
       Draw Behind: false
@@ -92,7 +117,7 @@ Visualization Manager:
       Unreliable: false
       Use Timestamp: false
       Value: true
-    - Alpha: 0.600000024
+    - Alpha: 0.6000000238418579
       Class: rviz/Map
       Color Scheme: costmap
       Draw Behind: false
@@ -127,15 +152,13 @@ Visualization Manager:
       Enabled: true
       Invert Rainbow: false
       Max Color: 255; 255; 255
-      Max Intensity: 1016
       Min Color: 0; 0; 0
-      Min Intensity: 1008
       Name: LaserScan
       Position Transformer: XYZ
       Queue Size: 10
       Selectable: true
       Size (Pixels): 3
-      Size (m): 0.00999999978
+      Size (m): 0.009999999776482582
       Style: Flat Squares
       Topic: /scan
       Unreliable: false
@@ -152,6 +175,11 @@ Visualization Manager:
         Expand Link Details: false
         Expand Tree: false
         Link Tree Style: Links in Alphabetic Order
+        back_wheel_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
         base_footprint:
           Alpha: 1
           Show Axes: false
@@ -167,11 +195,36 @@ Visualization Manager:
           Show Axes: false
           Show Trail: false
           Value: true
+        front_wheel_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        left_wheel_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
         lidar:
           Alpha: 1
           Show Axes: false
           Show Trail: false
           Value: true
+        right_wheel_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        servo_left_right_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        servo_up_down_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
       Name: RobotModel
       Robot Description: robot_description
       TF Prefix: ""
@@ -183,11 +236,11 @@ Visualization Manager:
       Class: rviz/Path
       Color: 44; 65; 255
       Enabled: true
-      Head Diameter: 0.300000012
-      Head Length: 0.200000003
-      Length: 0.300000012
+      Head Diameter: 0.30000001192092896
+      Head Length: 0.20000000298023224
+      Length: 0.30000001192092896
       Line Style: Lines
-      Line Width: 0.0299999993
+      Line Width: 0.029999999329447746
       Name: Path
       Offset:
         X: 0
@@ -195,10 +248,10 @@ Visualization Manager:
         Z: 0
       Pose Color: 255; 85; 255
       Pose Style: None
-      Radius: 0.0299999993
-      Shaft Diameter: 0.100000001
-      Shaft Length: 0.100000001
-      Topic: /move_base/DWAPlannerROS/global_plan
+      Radius: 0.029999999329447746
+      Shaft Diameter: 0.10000000149011612
+      Shaft Length: 0.10000000149011612
+      Topic: /move_base/GlobalPlanner/plan
       Unreliable: false
       Value: true
     - Alpha: 1
@@ -206,11 +259,11 @@ Visualization Manager:
       Class: rviz/Path
       Color: 255; 29; 218
       Enabled: true
-      Head Diameter: 0.300000012
-      Head Length: 0.200000003
-      Length: 0.300000012
+      Head Diameter: 0.30000001192092896
+      Head Length: 0.20000000298023224
+      Length: 0.30000001192092896
       Line Style: Lines
-      Line Width: 0.0299999993
+      Line Width: 0.029999999329447746
       Name: Path
       Offset:
         X: 0
@@ -218,9 +271,9 @@ Visualization Manager:
         Z: 0
       Pose Color: 255; 85; 255
       Pose Style: None
-      Radius: 0.0299999993
-      Shaft Diameter: 0.100000001
-      Shaft Length: 0.100000001
+      Radius: 0.029999999329447746
+      Shaft Diameter: 0.10000000149011612
+      Shaft Length: 0.10000000149011612
       Topic: /move_base/DWAPlannerROS/local_plan
       Unreliable: false
       Value: true
@@ -232,7 +285,7 @@ Visualization Manager:
       Topic: /move_base/global_costmap/footprint
       Unreliable: false
       Value: true
-    - Angle Tolerance: 0.0500000007
+    - Angle Tolerance: 0.05000000074505806
       Class: rviz/Odometry
       Covariance:
         Orientation:
@@ -244,7 +297,7 @@ Visualization Manager:
           Scale: 1
           Value: true
         Position:
-          Alpha: 0.300000012
+          Alpha: 0.30000001192092896
           Color: 204; 51; 204
           Scale: 1
           Value: true
@@ -252,20 +305,43 @@ Visualization Manager:
       Enabled: true
       Keep: 100
       Name: Odometry
-      Position Tolerance: 0.0500000007
+      Position Tolerance: 0.05000000074505806
       Shape:
         Alpha: 0.5
         Axes Length: 1
-        Axes Radius: 0.100000001
+        Axes Radius: 0.10000000149011612
         Color: 255; 0; 0
-        Head Length: 0.0500000007
-        Head Radius: 0.0500000007
-        Shaft Length: 0.0500000007
-        Shaft Radius: 0.0199999996
+        Head Length: 0.05000000074505806
+        Head Radius: 0.05000000074505806
+        Shaft Length: 0.05000000074505806
+        Shaft Radius: 0.019999999552965164
         Value: Arrow
       Topic: /odom_ekf
       Unreliable: false
       Value: true
+    - Alpha: 1
+      Buffer Length: 1
+      Class: rviz/Path
+      Color: 25; 255; 0
+      Enabled: true
+      Head Diameter: 0.30000001192092896
+      Head Length: 0.20000000298023224
+      Length: 0.30000001192092896
+      Line Style: Lines
+      Line Width: 0.029999999329447746
+      Name: Path
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Pose Color: 255; 85; 255
+      Pose Style: None
+      Radius: 0.029999999329447746
+      Shaft Diameter: 0.10000000149011612
+      Shaft Length: 0.10000000149011612
+      Topic: /move_base/TebLocalPlannerROS/local_plan
+      Unreliable: false
+      Value: true
   Enabled: true
   Global Options:
     Background Color: 45; 32; 41
@@ -281,7 +357,10 @@ Visualization Manager:
     - Class: rviz/FocusCamera
     - Class: rviz/Measure
     - Class: rviz/SetInitialPose
+      Theta std deviation: 0.2617993950843811
       Topic: /initialpose
+      X std deviation: 0.5
+      Y std deviation: 0.5
     - Class: rviz/SetGoal
       Topic: /move_base_simple/goal
     - Class: rviz/PublishPoint
@@ -291,33 +370,33 @@ Visualization Manager:
   Views:
     Current:
       Class: rviz/Orbit
-      Distance: 4.64580727
+      Distance: 4.645807266235352
       Enable Stereo Rendering:
-        Stereo Eye Separation: 0.0599999987
+        Stereo Eye Separation: 0.05999999865889549
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
       Focal Point:
-        X: 1.49610639
-        Y: -0.156017661
-        Z: 0.169606268
+        X: 1.1761776208877563
+        Y: 0.12880270183086395
+        Z: 0.183502197265625
       Focal Shape Fixed Size: true
-      Focal Shape Size: 0.0500000007
+      Focal Shape Size: 0.05000000074505806
       Invert Z Axis: false
       Name: Current View
-      Near Clip Distance: 0.00999999978
-      Pitch: 1.1997968
+      Near Clip Distance: 0.009999999776482582
+      Pitch: 1.5197967290878296
       Target Frame: <Fixed Frame>
       Value: Orbit (rviz)
-      Yaw: 4.7037096
+      Yaw: 4.673709392547607
     Saved: ~
 Window Geometry:
   Displays:
     collapsed: true
-  Height: 1056
+  Height: 803
   Hide Left Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000007800000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000251fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000004400000251000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004ab00000044fc0100000002fb0000000800540069006d00650100000000000004ab0000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ab0000027400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
@@ -326,6 +405,6 @@ Window Geometry:
     collapsed: false
   Views:
     collapsed: true
-  Width: 1920
-  X: 1600
-  Y: 24
+  Width: 1195
+  X: 18
+  Y: 162

Some files were not shown because too many files changed in this diff