Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@
<gazebo reference="camera_link">
<sensor name="camera" type="rgbd_camera">
<topic>camera</topic>
<gz_frame_id>camera_link</gz_frame_id>
<update_rate>30.0</update_rate>
<always_on>true</always_on>
<visualize>true</visualize>
Expand Down
1 change: 0 additions & 1 deletion linorobot2_description/urdf/sensors/imu.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
<gazebo reference="imu_link">
<sensor name="imu_sensor" type="imu">
<topic>imu/data</topic>
<gz_frame_id>imu_link</gz_frame_id>
<update_rate>50</update_rate>
<always_on>true</always_on>
<visualize>true</visualize>
Expand Down
23 changes: 22 additions & 1 deletion linorobot2_navigation/launch/navigation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,12 +61,33 @@ def generate_launch_description():
description='Navigation map path'
),

DeclareLaunchArgument(
name='initial_pose_x',
default_value='0.5',
description='Initial robot X position'
),

DeclareLaunchArgument(
name='initial_pose_y',
default_value='0.0',
description='Initial robot Y position'
),

DeclareLaunchArgument(
name='initial_pose_yaw',
default_value='0.0',
description='Initial robot yaw'
),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(nav2_launch_path),
launch_arguments={
'map': LaunchConfiguration("map"),
'use_sim_time': LaunchConfiguration("sim"),
'params_file': nav2_config_path
'params_file': nav2_config_path,
'initial_pose_x': LaunchConfiguration('initial_pose_x'),
'initial_pose_y': LaunchConfiguration('initial_pose_y'),
'initial_pose_yaw': LaunchConfiguration('initial_pose_yaw')
}.items()
),

Expand Down
35 changes: 28 additions & 7 deletions linorobot2_navigation/launch/slam.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,20 +63,41 @@ def generate_launch_description():
default_value='false',
description='Run rviz'
),
DeclareLaunchArgument(
name='initial_pose_x',
default_value='0.5',
description='Initial robot X position'
),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(navigation_launch_path),
launch_arguments={
'use_sim_time': LaunchConfiguration("sim"),
'params_file': nav2_config_path
}.items()
DeclareLaunchArgument(
name='initial_pose_y',
default_value='0.0',
description='Initial robot Y position'
),

DeclareLaunchArgument(
name='initial_pose_yaw',
default_value='0.0',
description='Initial robot yaw'
),

# IncludeLaunchDescription(
# PythonLaunchDescriptionSource(navigation_launch_path),
# launch_arguments={
# 'use_sim_time': LaunchConfiguration("sim"),
# 'params_file': nav2_config_path
# }.items()
# ),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(slam_launch_path),
launch_arguments={
'use_sim_time': LaunchConfiguration("sim"),
slam_param_name: slam_config_path
slam_param_name: slam_config_path,
# Pass the initial pose to slam_toolbox
'initial_pose_x': LaunchConfiguration('initial_pose_x'),
'initial_pose_y': LaunchConfiguration('initial_pose_y'),
'initial_pose_yaw': LaunchConfiguration('initial_pose_yaw')
}.items()
),

Expand Down
2 changes: 1 addition & 1 deletion linorobot2_navigation/rviz/linorobot2_slam.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ Visualization Manager:
Value: true
Views:
Current:
Angle: 0
Angle: -1.5599987506866455
Class: rviz_default_plugins/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Expand Down