Skip to content

Commit e90b54c

Browse files
committed
fixing up for use
1 parent acf5f5d commit e90b54c

File tree

3 files changed

+23
-3
lines changed

3 files changed

+23
-3
lines changed

nav2_min_tb4_description/urdf/standard/turtlebot4.urdf.xacro

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,26 @@
4646
<origin xyz="0 0 ${shell_z_offset + base_link_z_offset}" rpy="0 0 0"/>
4747
</joint>
4848

49+
<!-- Add a base footprint definition -->
50+
<joint name="base_footprint_joint" type="fixed">
51+
<parent link="base_link"/>
52+
<child link="base_footprint"/>
53+
<origin xyz="0 0 0" rpy="0 0 0"/>
54+
</joint>
55+
<link name="base_footprint">
56+
<inertial>
57+
<mass value="0.0001"/>
58+
<origin xyz="0 0 0"/>
59+
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
60+
</inertial>
61+
<visual>
62+
<origin rpy="0 0 0" xyz="0 0 0"/>
63+
<geometry>
64+
<box size="0.001 0.001 0.001"/>
65+
</geometry>
66+
</visual>
67+
</link>
68+
4969
<!-- Turtlebot4 shell definition -->
5070
<link name="shell_link">
5171
<visual>

nav2_min_tb4_sim/launch/simulation.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ def generate_launch_description():
125125
)
126126

127127
declare_robot_name_cmd = DeclareLaunchArgument(
128-
'robot_name', default_value='turtlebot3_waffle', description='name of the robot'
128+
'robot_name', default_value='nav2_turtlebot4', description='name of the robot'
129129
)
130130

131131
declare_robot_sdf_cmd = DeclareLaunchArgument(

nav2_min_tb4_sim/launch/spawn_tb4.launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ def generate_launch_description():
3636
use_simulator = LaunchConfiguration('use_simulator')
3737
robot_name = LaunchConfiguration('robot_name')
3838
robot_sdf = LaunchConfiguration('robot_sdf')
39-
pose = {'x': LaunchConfiguration('x_pose', default='-2.00'),
39+
pose = {'x': LaunchConfiguration('x_pose', default='-8.00'),
4040
'y': LaunchConfiguration('y_pose', default='-0.50'),
4141
'z': LaunchConfiguration('z_pose', default='0.01'),
4242
'R': LaunchConfiguration('roll', default='0.00'),
@@ -113,7 +113,7 @@ def generate_launch_description():
113113
arguments=[
114114
'-entity', robot_name,
115115
'-topic', 'robot_description',
116-
# '-file', Command(['xacro', ' ', robot_sdf]), # TODO robot SDF file just unhappy.
116+
# '-file', Command(['xacro', ' ', robot_sdf]), # TODO SDF file is unhappy, not sure why
117117
'-robot_namespace', namespace,
118118
'-x', pose['x'], '-y', pose['y'], '-z', pose['z'],
119119
'-R', pose['R'], '-P', pose['P'], '-Y', pose['Y']],

0 commit comments

Comments
 (0)