diff --git a/nav2_system_tests/src/updown/test_updown_launch.py b/nav2_system_tests/src/updown/test_updown_launch.py index 1e2b4891ef47a91a7dd14f7b5577d0d294f3d4f4..8f75db644eb0919d57484aa7b5eb6b08da91c961 100755 --- a/nav2_system_tests/src/updown/test_updown_launch.py +++ b/nav2_system_tests/src/updown/test_updown_launch.py @@ -40,7 +40,7 @@ def generate_launch_description(): declare_urdf_cmd = launch.actions.DeclareLaunchArgument( 'urdf', default_value=[launch.substitutions.ThisLaunchFileDir(), - '/../../urdf/turtlebot3_burger.urdf'], + '/../../urdf/turtlebot3_waffle.urdf'], description='Full path to model file to load') launch_dir = os.path.join( diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo.world index 461dd137daf7652c43dde78705bb4cb7ae6d78ab..9e2cd7ce27f6e2ee6ff8426c39b3c6e224c02109 100644 --- a/nav2_system_tests/worlds/turtlebot3_ros2_demo.world +++ b/nav2_system_tests/worlds/turtlebot3_ros2_demo.world @@ -58,7 +58,7 @@ <link name="base_link"> <inertial> - <pose>-0.032 0 0.070 0 0 0</pose> + <pose>-0.064 0 0.048 0 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -71,19 +71,19 @@ </inertial> <collision name="base_collision"> - <pose>-0.032 0 0.070 0 0 0</pose> + <pose>-0.064 0 0.048 0 0 0</pose> <geometry> <box> - <size>0.140 0.140 0.140</size> + <size>0.265 0.265 0.089</size> </box> </geometry> </collision> <visual name="base_visual"> - <pose>-0.032 0 0 0 0 0</pose> + <pose>-0.064 0 0 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/burger_base.dae</uri> + <uri>model://turtlebot3_waffle/meshes/waffle_base.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> @@ -149,7 +149,7 @@ <link name="base_scan"> <inertial> - <pose>-0.020 0 0.161 0 0 0</pose> + <pose>-0.052 0 0.111 0 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -162,7 +162,7 @@ </inertial> <collision name="lidar_sensor_collision"> - <pose>-0.020 0 0.161 0 0 0</pose> + <pose>-0.064 0 0.121 0 0 0</pose> <geometry> <cylinder> <radius>0.0508</radius> @@ -175,7 +175,7 @@ <pose>-0.032 0 0.171 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/lds.dae</uri> + <uri>model://turtlebot3_waffle/meshes/lds.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> @@ -184,7 +184,7 @@ <sensor name="hls_lfcd_lds" type="ray"> <always_on>true</always_on> <visualize>false</visualize> - <pose>-0.032 0 0.171 0 0 0</pose> + <pose>-0.064 0 0.121 0 0 0</pose> <update_rate>5</update_rate> <ray> <scan> @@ -221,7 +221,7 @@ <link name="wheel_left_link"> <inertial> - <pose>0 0.08 0.023 -1.57 0 0</pose> + <pose>0.0 0.144 0.023 -1.57 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -234,7 +234,7 @@ </inertial> <collision name="wheel_left_collision"> - <pose>0 0.08 0.023 -1.57 0 0</pose> + <pose>0.0 0.144 0.023 -1.57 0 0</pose> <geometry> <cylinder> <radius>0.033</radius> @@ -266,10 +266,10 @@ </collision> <visual name="wheel_left_visual"> - <pose>0 0.08 0.023 0 0 0</pose> + <pose>0.0 0.144 0.023 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/left_tire.dae</uri> + <uri>model://turtlebot3_waffle/meshes/left_tire.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> @@ -279,7 +279,7 @@ <link name="wheel_right_link"> <inertial> - <pose>0.0 -0.08 0.023 -1.57 0 0</pose> + <pose>0.0 -0.144 0.023 -1.57 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -292,7 +292,7 @@ </inertial> <collision name="wheel_right_collision"> - <pose>0.0 -0.08 0.023 -1.57 0 0</pose> + <pose>0.0 -0.144 0.023 -1.57 0 0</pose> <geometry> <cylinder> <radius>0.033</radius> @@ -324,18 +324,52 @@ </collision> <visual name="wheel_right_visual"> - <pose>0.0 -0.08 0.023 0 0 0</pose> + <pose>0.0 -0.144 0.023 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/right_tire.dae</uri> + <uri>model://turtlebot3_waffle/meshes/right_tire.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> </visual> </link> - <link name='caster_back_link'> - <pose>-0.081 0 -0.004 0 0 0</pose> + <link name='caster_back_right_link'> + <pose>-0.177 -0.064 -0.004 0 0 0</pose> + <inertial> + <mass>0.001</mass> + <inertia> + <ixx>0.00001</ixx> + <ixy>0.000</ixy> + <ixz>0.000</ixz> + <iyy>0.00001</iyy> + <iyz>0.000</iyz> + <izz>0.00001</izz> + </inertia> + </inertial> + <collision name='collision'> + <geometry> + <sphere> + <radius>0.005000</radius> + </sphere> + </geometry> + <surface> + <contact> + <ode> + <soft_cfm>0</soft_cfm> + <soft_erp>0.2</soft_erp> + <kp>1e+5</kp> + <kd>1</kd> + <max_vel>0.01</max_vel> + <min_depth>0.001</min_depth> + </ode> + </contact> + </surface> + </collision> + </link> + + <link name='caster_back_left_link'> + <pose>-0.177 0.064 -0.004 0 0 0</pose> <inertial> <mass>0.001</mass> <inertia> @@ -377,7 +411,7 @@ <joint name="wheel_left_joint" type="revolute"> <parent>base_link</parent> <child>wheel_left_link</child> - <pose>0.0 0.08 0.023 -1.57 0 0</pose> + <pose>0.0 0.144 0.023 -1.57 0 0</pose> <axis> <xyz>0 0 1</xyz> </axis> @@ -386,15 +420,20 @@ <joint name="wheel_right_joint" type="revolute"> <parent>base_link</parent> <child>wheel_right_link</child> - <pose>0.0 -0.08 0.023 -1.57 0 0</pose> + <pose>0.0 -0.144 0.023 -1.57 0 0</pose> <axis> <xyz>0 0 1</xyz> </axis> </joint> - <joint name='caster_back_joint' type='ball'> + <joint name='caster_back_right_joint' type='ball'> + <parent>base_link</parent> + <child>caster_back_right_link</child> + </joint> + + <joint name='caster_back_left_joint' type='ball'> <parent>base_link</parent> - <child>caster_back_link</child> + <child>caster_back_left_link</child> </joint> <joint name="imu_joint" type="fixed"> @@ -409,7 +448,7 @@ <joint name="lidar_joint" type="fixed"> <parent>base_link</parent> <child>base_scan</child> - <pose>-0.032 0 0.171 0 0 0</pose> + <pose>-0.064 0 0.121 0 0 0</pose> <axis> <xyz>0 0 1</xyz> </axis> @@ -426,7 +465,7 @@ <right_joint>wheel_right_joint</right_joint> <!-- kinematics --> - <wheel_separation>0.160</wheel_separation> + <wheel_separation>0.287</wheel_separation> <wheel_diameter>0.066</wheel_diameter> <!-- limits --> diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world index 0ae12a416a3633c2e00da695217197dfea6c3f82..eed22268175e0ccc367bdb5103e5db35b43bde2e 100644 --- a/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world +++ b/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world @@ -58,7 +58,7 @@ <link name="base_link"> <inertial> - <pose>-0.032 0 0.070 0 0 0</pose> + <pose>-0.064 0 0.048 0 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -71,19 +71,19 @@ </inertial> <collision name="base_collision"> - <pose>-0.032 0 0.070 0 0 0</pose> + <pose>-0.064 0 0.048 0 0 0</pose> <geometry> <box> - <size>0.140 0.140 0.140</size> + <size>0.265 0.265 0.089</size> </box> </geometry> </collision> <visual name="base_visual"> - <pose>-0.032 0 0 0 0 0</pose> + <pose>-0.064 0 0 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/burger_base.dae</uri> + <uri>model://turtlebot3_waffle/meshes/waffle_base.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> @@ -149,7 +149,7 @@ <link name="base_scan"> <inertial> - <pose>-0.020 0 0.161 0 0 0</pose> + <pose>-0.052 0 0.111 0 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -172,10 +172,10 @@ </collision> <visual name="lidar_sensor_visual"> - <pose>-0.032 0 0.171 0 0 0</pose> + <pose>-0.064 0 0.121 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/lds.dae</uri> + <uri>model://turtlebot3_waffle/meshes/lds.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> @@ -184,7 +184,7 @@ <sensor name="hls_lfcd_lds" type="ray"> <always_on>true</always_on> <visualize>false</visualize> - <pose>-0.032 0 0.171 0 0 0</pose> + <pose>-0.064 0 0.121 0 0 0</pose> <update_rate>5</update_rate> <ray> <scan> @@ -221,7 +221,7 @@ <link name="wheel_left_link"> <inertial> - <pose>0 0.08 0.023 -1.57 0 0</pose> + <pose>0.0 0.144 0.023 -1.57 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -234,7 +234,7 @@ </inertial> <collision name="wheel_left_collision"> - <pose>0 0.08 0.023 -1.57 0 0</pose> + <pose>0.0 0.144 0.023 -1.57 0 0</pose> <geometry> <cylinder> <radius>0.033</radius> @@ -266,10 +266,10 @@ </collision> <visual name="wheel_left_visual"> - <pose>0 0.08 0.023 0 0 0</pose> + <pose>0.0 0.144 0.023 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/left_tire.dae</uri> + <uri>model://turtlebot3_waffle/meshes/left_tire.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> @@ -279,7 +279,7 @@ <link name="wheel_right_link"> <inertial> - <pose>0.0 -0.08 0.023 -1.57 0 0</pose> + <pose>0.0 -0.144 0.023 -1.57 0 0</pose> <inertia> <ixx>0.001</ixx> <ixy>0.000</ixy> @@ -292,7 +292,7 @@ </inertial> <collision name="wheel_right_collision"> - <pose>0.0 -0.08 0.023 -1.57 0 0</pose> + <pose>0.0 -0.144 0.023 -1.57 0 0</pose> <geometry> <cylinder> <radius>0.033</radius> @@ -324,18 +324,52 @@ </collision> <visual name="wheel_right_visual"> - <pose>0.0 -0.08 0.023 0 0 0</pose> + <pose>0.0 -0.144 0.023 0 0 0</pose> <geometry> <mesh> - <uri>model://turtlebot3_burger/meshes/right_tire.dae</uri> + <uri>model://turtlebot3_waffle/meshes/right_tire.dae</uri> <scale>0.001 0.001 0.001</scale> </mesh> </geometry> </visual> </link> - <link name='caster_back_link'> - <pose>-0.081 0 -0.004 0 0 0</pose> + <link name='caster_back_right_link'> + <pose>-0.177 -0.064 -0.004 0 0 0</pose> + <inertial> + <mass>0.001</mass> + <inertia> + <ixx>0.00001</ixx> + <ixy>0.000</ixy> + <ixz>0.000</ixz> + <iyy>0.00001</iyy> + <iyz>0.000</iyz> + <izz>0.00001</izz> + </inertia> + </inertial> + <collision name='collision'> + <geometry> + <sphere> + <radius>0.005000</radius> + </sphere> + </geometry> + <surface> + <contact> + <ode> + <soft_cfm>0</soft_cfm> + <soft_erp>0.2</soft_erp> + <kp>1e+5</kp> + <kd>1</kd> + <max_vel>0.01</max_vel> + <min_depth>0.001</min_depth> + </ode> + </contact> + </surface> + </collision> + </link> + + <link name='caster_back_left_link'> + <pose>-0.177 0.064 -0.004 0 0 0</pose> <inertial> <mass>0.001</mass> <inertia> @@ -377,7 +411,7 @@ <joint name="wheel_left_joint" type="revolute"> <parent>base_link</parent> <child>wheel_left_link</child> - <pose>0.0 0.08 0.023 -1.57 0 0</pose> + <pose>0.0 0.144 0.023 -1.57 0 0</pose> <axis> <xyz>0 0 1</xyz> </axis> @@ -386,15 +420,20 @@ <joint name="wheel_right_joint" type="revolute"> <parent>base_link</parent> <child>wheel_right_link</child> - <pose>0.0 -0.08 0.023 -1.57 0 0</pose> + <pose>0.0 -0.144 0.023 -1.57 0 0</pose> <axis> <xyz>0 0 1</xyz> </axis> </joint> - <joint name='caster_back_joint' type='ball'> + <joint name='caster_back_right_joint' type='ball'> + <parent>base_link</parent> + <child>caster_back_right_link</child> + </joint> + + <joint name='caster_back_left_joint' type='ball'> <parent>base_link</parent> - <child>caster_back_link</child> + <child>caster_back_left_link</child> </joint> <joint name="imu_joint" type="fixed"> @@ -409,7 +448,7 @@ <joint name="lidar_joint" type="fixed"> <parent>base_link</parent> <child>base_scan</child> - <pose>-0.032 0 0.171 0 0 0</pose> + <pose>-0.064 0 0.121 0 0 0</pose> <axis> <xyz>0 0 1</xyz> </axis> @@ -426,7 +465,7 @@ <right_joint>wheel_right_joint</right_joint> <!-- kinematics --> - <wheel_separation>0.160</wheel_separation> + <wheel_separation>0.287</wheel_separation> <wheel_diameter>0.066</wheel_diameter> <!-- limits -->