diff --git a/src/igvc_description/urdf/robot.urdf.xacro b/src/igvc_description/urdf/robot.urdf.xacro index fdf462af..89cdcfd9 100644 --- a/src/igvc_description/urdf/robot.urdf.xacro +++ b/src/igvc_description/urdf/robot.urdf.xacro @@ -4,14 +4,22 @@ + - + + + + + + + + diff --git a/src/igvc_description/urdf/sensor/camera.urdf.xacro b/src/igvc_description/urdf/sensor/camera.urdf.xacro index adb11647..9cd82e80 100644 --- a/src/igvc_description/urdf/sensor/camera.urdf.xacro +++ b/src/igvc_description/urdf/sensor/camera.urdf.xacro @@ -14,7 +14,7 @@ - + diff --git a/src/igvc_description/urdf/sensor/gps.urdf.xacro b/src/igvc_description/urdf/sensor/gps.urdf.xacro index 620efe6d..2fed30fc 100644 --- a/src/igvc_description/urdf/sensor/gps.urdf.xacro +++ b/src/igvc_description/urdf/sensor/gps.urdf.xacro @@ -2,7 +2,7 @@ - + diff --git a/src/igvc_description/urdf/sensor/imu.urdf.xacro b/src/igvc_description/urdf/sensor/imu.urdf.xacro index 2cf6f2ff..9f2613ea 100644 --- a/src/igvc_description/urdf/sensor/imu.urdf.xacro +++ b/src/igvc_description/urdf/sensor/imu.urdf.xacro @@ -2,7 +2,7 @@ - + diff --git a/src/igvc_description/urdf/sensor/lidar.urdf.xacro b/src/igvc_description/urdf/sensor/lidar.urdf.xacro index 2354547f..e45f5cd1 100644 --- a/src/igvc_description/urdf/sensor/lidar.urdf.xacro +++ b/src/igvc_description/urdf/sensor/lidar.urdf.xacro @@ -1,7 +1,7 @@ - + diff --git a/src/igvc_nav/config/nav2_params.yaml b/src/igvc_nav/config/nav2_params.yaml index 32973563..613f4d1b 100644 --- a/src/igvc_nav/config/nav2_params.yaml +++ b/src/igvc_nav/config/nav2_params.yaml @@ -313,7 +313,7 @@ velocity_smoother: collision_monitor: ros__parameters: - base_frame_id: "base_footprint" + base_frame_id: "base_link" odom_frame_id: "odom" cmd_vel_in_topic: "cmd_vel_smoothed" cmd_vel_out_topic: "cmd_vel" diff --git a/src/igvc_slam/launch/rtabmap.launch.py b/src/igvc_slam/launch/rtabmap.launch.py index 958ad292..8810a6e5 100644 --- a/src/igvc_slam/launch/rtabmap.launch.py +++ b/src/igvc_slam/launch/rtabmap.launch.py @@ -38,7 +38,7 @@ def generate_launch_description(): 'depth_topic' : '/camera/camera/aligned_depth_to_color/image_raw', 'rgb_topic' : '/camera/camera/color/image_raw', 'camera_info_topic' : '/camera/camera/color/camera_info', - 'frame_id' : 'base_footprint', + 'frame_id' : 'base_link', 'publish_tf_odom' : 'true', 'odom_topic' : '/odom', 'odom_frame_id' : 'odom', diff --git a/src/igvc_slam/launch/sim_rtabmap.launch.py b/src/igvc_slam/launch/sim_rtabmap.launch.py index 41b3991f..31b40491 100644 --- a/src/igvc_slam/launch/sim_rtabmap.launch.py +++ b/src/igvc_slam/launch/sim_rtabmap.launch.py @@ -21,7 +21,7 @@ def generate_launch_description(): 'rgb_topic' : '/camera/camera/color/image_raw', 'camera_info_topic' : '/camera/camera/depth/camera_info', 'approx_sync' : 'true', - 'frame_id' : 'base_footprint', + 'frame_id' : 'base_link', 'log_level' : 'debug', 'publish_tf_odom' : 'true', 'odom_topic' : '/odom',