Skip to content

Commit

Permalink
Update gazebo and lidarbot bringup launch files
Browse files Browse the repository at this point in the history
  • Loading branch information
TheNoobInventor committed Oct 13, 2023
1 parent c3a4e9c commit 5af65f1
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 6 deletions.
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -691,6 +691,8 @@ TODO:
map_start_at_dock: true
```

TODO: Note about the option of using AMCL for localization using nav2's localization launch file. Currently using slam_toolbox for localization

### Lidarbot

Change `map_file_name` key to use real map
Expand Down
4 changes: 2 additions & 2 deletions lidarbot_bringup/launch/lidarbot_bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ def generate_launch_description():

# Spawn joint_state_broadcaser
start_joint_broadcaster_cmd = Node(
condition=IfCondition(use_ros2_control),
# condition=IfCondition(use_ros2_control),
package='controller_manager',
executable='spawner',
arguments=['joint_broadcaster'])
Expand All @@ -88,7 +88,7 @@ def generate_launch_description():

# Spawn imu_sensor_broadcaser
start_imu_broadcaster_cmd = Node(
condition=IfCondition(use_ros2_control),
# condition=IfCondition(use_ros2_control),
package='controller_manager',
executable='spawner',
arguments=['imu_broadcaster'])
Expand Down
23 changes: 20 additions & 3 deletions lidarbot_gazebo/launch/gazebo_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,9 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
use_ros2_control = LaunchConfiguration('use_ros2_control')
world = LaunchConfiguration('world')

use_robot_localization = LaunchConfiguration('use_robot_localization')

# Declare the launch arguments
declare_use_sim_time_cmd = DeclareLaunchArgument(
name='use_sim_time',
default_value='True',
Expand All @@ -48,7 +50,12 @@ def generate_launch_description():
name='world',
default_value=world_path,
description='Full path to the world model to load')


declare_use_robot_localization_cmd = DeclareLaunchArgument(
name='use_robot_localization',
default_value='True',
description='Use robot_localization package if true')

# Start robot state publisher
start_robot_state_publisher_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(pkg_description, 'launch', 'robot_state_publisher_launch.py')]),
Expand All @@ -74,6 +81,13 @@ def generate_launch_description():
package='controller_manager',
executable='spawner',
arguments=['diff_controller'])

# Spawn imu_sensor_broadcaser
start_imu_broadcaster_cmd = Node(
condition=IfCondition(use_ros2_control),
package='controller_manager',
executable='spawner',
arguments=['imu_broadcaster'])

# Spawn joint_state_broadcaser
start_joint_broadcaster_cmd = Node(
Expand All @@ -84,6 +98,7 @@ def generate_launch_description():

# Start robot localization using an Extended Kalman Filter
start_robot_localization_cmd = Node(
condition=IfCondition(use_robot_localization),
package='robot_localization',
executable='ekf_node',
parameters=[ekf_params_file])
Expand All @@ -106,13 +121,15 @@ def generate_launch_description():
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_use_ros2_control_cmd)
ld.add_action(declare_world_cmd)

ld.add_action(declare_use_robot_localization_cmd)

# Add any actions
ld.add_action(start_robot_state_publisher_cmd)
ld.add_action(start_gazebo_cmd)
ld.add_action(start_spawner_cmd)
ld.add_action(start_diff_controller_cmd)
ld.add_action(start_joint_broadcaster_cmd)
ld.add_action(start_imu_broadcaster_cmd)
ld.add_action(start_robot_localization_cmd)
ld.add_action(start_joystick_cmd)
ld.add_action(start_twist_mux_cmd)
Expand Down
2 changes: 1 addition & 1 deletion lidarbot_navigation/config/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ local_costmap:
width: 3
height: 3
resolution: 0.05
robot_radius: 0.22
robot_radius: 0.14 #0.22
plugins: ["voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
Expand Down

0 comments on commit 5af65f1

Please sign in to comment.