2024-7-22launch测试

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode
from nav2_common.launch import RewrittenYaml

from launch.actions import (DeclareLaunchArgument, GroupAction,
                            IncludeLaunchDescription, SetEnvironmentVariable)
from launch.launch_description_sources import PythonLaunchDescriptionSource


def generate_launch_description():

    bringup_dir = get_package_share_directory('yhs_nav2')
    launch_dir = os.path.join(bringup_dir, 'launch')

    workspace_dir = os.path.dirname(os.path.dirname(os.path.dirname(os.path.realpath(__file__))))
    map_file_dir = os.path.join(workspace_dir, 'yhs_nav2', 'map')
    chassis_launch_dir = os.path.join(get_package_share_directory('yhs_can_control'),'launch')

    use_respawn = LaunchConfiguration('use_respawn')
    declare_use_respawn_cmd = DeclareLaunchArgument(
    'use_respawn', default_value='False',
    description='Whether to respawn if a node crashes. Applied when composition is disabled.')


    namespace = LaunchConfiguration('namespace')
    declare_namespace_cmd = DeclareLaunchArgument(
        'namespace',
        default_value='',
        description='Top-level namespace')


    use_sim_time = LaunchConfiguration('use_sim_time')
    declare_use_sim_time_cmd = DeclareLaunchArgument(
        'use_sim_time',
        default_value='false',
        description='Use simulation (Gazebo) clock if true')
    

    params_file = LaunchConfiguration('params_file')

    use_tf = LaunchConfiguration('use_tf')
    declare_use_tf_cmd = DeclareLaunchArgument('use_tf', default_value='true', description='is use_tf?')

    autostart = LaunchConfiguration('autostart')
    declare_autostart_cmd = DeclareLaunchArgument(
        'autostart', default_value='true',
        description='Automatically startup the nav2 stack')

    log_level = LaunchConfiguration('log_level')
    declare_log_level_cmd = DeclareLaunchArgument(
    'log_level', default_value='info',
    description='log level')

    map_yaml_file = LaunchConfiguration('map')

    declare_map_yaml_cmd = DeclareLaunchArgument(
    'map',
    default_value=os.path.join(map_file_dir, '416.yaml'),
    description='地图名称')

    lifecycle_nodes = ['behavior_server',
                       'controller_server',
                       'map_server',
                       'planner_server',
                       'bt_navigator',
                       'waypoint_follower',
                       'amcl']

    remappings = [('/tf', 'tf'),
                ('/tf_static', 'tf_static')]

    declare_params_file_cmd = DeclareLaunchArgument(
        'params_file',
        default_value=os.path.join(bringup_dir, 'param', 'yhs_nav2.yaml'),
        description='Full path to the ROS2 parameters file to use for all launched nodes')
    
    param_substitutions = {
        'use_sim_time': use_sim_time,
        'yaml_filename': map_yaml_file}
    
    configured_params = RewrittenYaml(
        source_file=params_file,
        root_key=namespace,
        param_rewrites=param_substitutions,
        convert_types=True)

    bringup_cmd_group = GroupAction([
        IncludeLaunchDescription(
        PythonLaunchDescriptionSource(os.path.join(chassis_launch_dir, 'yhs_can_control.launch.py')),
        launch_arguments={'namespace': namespace,
                            'use_sim_time': use_sim_time,
                            'autostart': autostart,
                            'use_respawn': use_respawn,
                            'use_tf': use_tf}.items()),

        Node(
        package='nav2_amcl',
        executable='amcl',
        name='amcl',
        output='screen',
        respawn=use_respawn,
        respawn_delay=2.0,
        parameters=[configured_params],
        arguments=['--ros-args', '--log-level', log_level],
        remappings=remappings),

        Node(
                package='nav2_behaviors',
                executable='behavior_server',
                name='behavior_server',
                output='screen',
                respawn=use_respawn,
                respawn_delay=2.0,
                parameters=[configured_params],
                arguments=['--ros-args', '--log-level', log_level],
                remappings=remappings),

        Node(
                package='nav2_controller',
                executable='controller_server',
                output='screen',
                respawn=use_respawn,
                respawn_delay=2.0,
                parameters=[configured_params],
                arguments=['--ros-args', '--log-level', log_level],
                remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),

        Node(
        name='nav2_container',
        package='rclcpp_components',
        executable='component_container_isolated',
        parameters=[configured_params, {'autostart': autostart}],
        arguments=['--ros-args', '--log-level', log_level],
        remappings=remappings,
        output='screen'),
        Node(
        package='nav2_bt_navigator',
        executable='bt_navigator',
        name='bt_navigator',
        output='screen',
        parameters=[configured_params],
        arguments=['--ros-args', '--log-level', log_level],
        remappings=remappings),

        Node(
        package='nav2_map_server',
        executable='map_server',
        name='map_server',
        parameters=[{'yaml_filename': os.path.join(map_file_dir, '416.yaml')}]
        ),

        Node(
                package='nav2_waypoint_follower',
                executable='waypoint_follower',
                name='waypoint_follower',
                output='screen',
                respawn=use_respawn,
                respawn_delay=2.0,
                parameters=[configured_params],
                arguments=['--ros-args', '--log-level', log_level],
                remappings=remappings),

        Node(
        package='nav2_planner',
        executable='planner_server',
        name='planner_server',
        parameters=[{
            'expected_planner_frequency': 2.0,
            'use_sim_time': False,
            'planner_plugins': ['GridBased'],
            'GridBased': {
                'plugin': 'nav2_navfn_planner/NavfnPlanner',
                'tolerance': 0.5,
                'use_astar': True,
                'allow_unknown': False,
                'smooth_path': True,
                'angle': 0.05
            }
        }]),

        Node(
        package='nav2_lifecycle_manager',
        executable='lifecycle_manager',
        name='lifecycle_manager',
        output='screen',
        parameters=[{'autostart': True},
                    {'node_names': lifecycle_nodes}]),

        Node(
        package='tf2_ros',
        executable='static_transform_publisher',
        name='static_transform_publisher',
        output='screen',
        arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'map']),
        
        # Node(
        #     package='tf2_ros',
        #     executable='static_transform_publisher',
        #     name='static_transform_publisher_odom_to_base_link',
        #     arguments=['0', '0', '0', '0', '0', '1', 'odom', 'base_link']
        # ),
        # Node(
        #     package='tf2_ros',
        #     executable='static_transform_publisher',
        #     name='static_transform_publisher_map_to_odom',
        #     arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom']),
        # Node(
        #     package='tf2_ros',
        #     executable='static_transform_publisher',
        #     name='static_transform_publisher_odom_to_base_link',
        #     arguments=['1', '3', '4', '0', '0', '1', 'odom', 'base_link']),
    ])

    ld = LaunchDescription()

    ld.add_action(declare_namespace_cmd)
    ld.add_action(declare_params_file_cmd)

    ld.add_action(declare_use_sim_time_cmd)  
    ld.add_action(declare_autostart_cmd)
    ld.add_action(declare_log_level_cmd)
    ld.add_action(declare_map_yaml_cmd)
    ld.add_action(declare_use_respawn_cmd)
    ld.add_action(declare_use_tf_cmd)

    ld.add_action(bringup_cmd_group)

   

    return ld



评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

acanab

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值