From 62315deaa8828fb30df1f56628939e5ce6a7cf85 Mon Sep 17 00:00:00 2001 From: TheNoobInventor Date: Sun, 25 Aug 2024 23:13:32 +0100 Subject: [PATCH] Update real and Gazebo Fortress lidarbot bringup launch files --- .../launch/lidarbot_bringup_launch.py | 63 +++++++------------ lidarbot_gz/launch/gz_launch.py | 36 ++++------- 2 files changed, 34 insertions(+), 65 deletions(-) diff --git a/lidarbot_bringup/launch/lidarbot_bringup_launch.py b/lidarbot_bringup/launch/lidarbot_bringup_launch.py index 2e16c71..936090e 100644 --- a/lidarbot_bringup/launch/lidarbot_bringup_launch.py +++ b/lidarbot_bringup/launch/lidarbot_bringup_launch.py @@ -9,7 +9,6 @@ from launch import LaunchDescription from launch.actions import ( DeclareLaunchArgument, - ExecuteProcess, IncludeLaunchDescription, TimerAction, RegisterEventHandler, @@ -85,43 +84,25 @@ def generate_launch_description(): parameters=[{"robot_description": robot_description}, controller_params_file], ) - # Start joint_state_broadcaster - load_joint_state_broadcaster = ExecuteProcess( - cmd=[ - "ros2", - "control", - "load_controller", - "--set-state", - "active", - "joint_broadcaster", - ], - output="screen", - ) - - # Start diff_drive_controller - load_diff_drive_controller = ExecuteProcess( - cmd=[ - "ros2", - "control", - "load_controller", - "--set-state", - "active", - "diff_controller", - ], - output="screen", - ) - - # Start imu_sensor_broadcaster - load_imu_sensor_broadcaster = ExecuteProcess( - cmd=[ - "ros2", - "control", - "load_controller", - "--set-state", - "active", - "imu_broadcaster", - ], - output="screen", + # Spawn diff_controller + start_diff_controller_cmd = Node( + package="controller_manager", + executable="spawner", + arguments=["diff_controller", "--controller-manager", "/controller_manager"], + ) + + # Spawn joint_state_broadcaser + start_joint_broadcaster_cmd = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_broadcaster", "--controller-manager", "/controller_manager"], + ) + + # Spawn imu_sensor_broadcaster + start_imu_broadcaster_cmd = Node( + package="controller_manager", + executable="spawner", + arguments=["imu_broadcaster", "--controller-manager", "/controller_manager"], ) # Delayed controller manager action @@ -133,7 +114,7 @@ def generate_launch_description(): start_delayed_diff_drive_spawner = RegisterEventHandler( event_handler=OnProcessStart( target_action=start_controller_manager_cmd, - on_start=[load_diff_drive_controller], + on_start=[start_diff_controller_cmd], ) ) @@ -141,7 +122,7 @@ def generate_launch_description(): start_delayed_joint_broadcaster_spawner = RegisterEventHandler( event_handler=OnProcessStart( target_action=start_controller_manager_cmd, - on_start=[load_joint_state_broadcaster], + on_start=[start_joint_broadcaster_cmd], ) ) @@ -149,7 +130,7 @@ def generate_launch_description(): start_delayed_imu_broadcaster_spawner = RegisterEventHandler( event_handler=OnProcessStart( target_action=start_controller_manager_cmd, - on_start=[load_imu_sensor_broadcaster], + on_start=[start_imu_broadcaster_cmd], ) ) diff --git a/lidarbot_gz/launch/gz_launch.py b/lidarbot_gz/launch/gz_launch.py index 141a53e..d808f4a 100644 --- a/lidarbot_gz/launch/gz_launch.py +++ b/lidarbot_gz/launch/gz_launch.py @@ -133,30 +133,18 @@ def generate_launch_description(): output="screen", ) - # Start joint_state_broadcaster - load_joint_state_broadcaster = ExecuteProcess( - cmd=[ - "ros2", - "control", - "load_controller", - "--set-state", - "active", - "joint_broadcaster", - ], - output="screen", + # Spawn diff_controller + start_diff_controller_cmd = Node( + package="controller_manager", + executable="spawner", + arguments=["diff_controller", "--controller-manager", "/controller_manager"], ) - # Start diff_drive_controller - load_diff_drive_controller = ExecuteProcess( - cmd=[ - "ros2", - "control", - "load_controller", - "--set-state", - "active", - "diff_controller", - ], - output="screen", + # Spawn joint_state_broadcaser + start_joint_broadcaster_cmd = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_broadcaster", "--controller-manager", "/controller_manager"], ) # Start robot localization using an Extended Kalman Filter @@ -200,8 +188,8 @@ def generate_launch_description(): ld.add_action(start_gazebo_ros_bridge_cmd) ld.add_action(start_gazebo_ros_image_bridge_cmd) ld.add_action(start_robot_localization_cmd) - ld.add_action(load_diff_drive_controller) - ld.add_action(load_joint_state_broadcaster) + ld.add_action(start_diff_controller_cmd) + ld.add_action(start_joint_broadcaster_cmd) ld.add_action(start_joystick_cmd) ld.add_action(start_twist_mux_cmd)