From cb849b521a1aec43d2d61bc640b637f07ecc2b09 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Galambos=20Mih=C3=A1ly?= <galambos.mihaly@hallgato.ppke.hu> Date: Thu, 21 Apr 2022 13:55:47 +0200 Subject: [PATCH] Separate simulation and description bringup --- .../launch/description.launch.py | 51 +++++++++++++++++++ .../launch/simulation.launch.py | 39 ++++---------- 2 files changed, 62 insertions(+), 28 deletions(-) create mode 100644 src/hollander_bringup/launch/description.launch.py diff --git a/src/hollander_bringup/launch/description.launch.py b/src/hollander_bringup/launch/description.launch.py new file mode 100644 index 0000000..020a9fc --- /dev/null +++ b/src/hollander_bringup/launch/description.launch.py @@ -0,0 +1,51 @@ +import os + +from launch_ros.actions import Node +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import Command, LaunchConfiguration +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + + # Get package dirs + package_dir = get_package_share_directory('hollander_description') + + # Default values + default_model_path = os.path.join(package_dir, 'src/description/rollende_hollander.urdf') + + configurable_parameters = [ + {'name': 'model', 'default': default_model_path, 'description': 'Absolute path to robot urdf file'}, + {'name': 'namespace', 'default': 'hollander', 'description': 'Namespace to avoide conflicts'}, + {'name': 'log_level', 'default': 'info', 'description': 'debug log level [DEBUG|INFO|WARN|ERROR|FATAL]'}, + ] + + def declare_configurable_parameters(parameters): + return [DeclareLaunchArgument(param['name'], default_value=param['default'], description=param['description']) for param in parameters] + + + """ NODES """ + robot_state_publisher_node = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + namespace=LaunchConfiguration("namespace"), + parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}], + arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')], + emulate_tty=True, + ) + + joint_state_publisher_node = Node( + package='joint_state_publisher', + executable='joint_state_publisher', + name='joint_state_publisher', + namespace=LaunchConfiguration("namespace"), + arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')], + emulate_tty=True, + ) + + return LaunchDescription(declare_configurable_parameters(configurable_parameters) + [ + robot_state_publisher_node, + joint_state_publisher_node, + ]) \ No newline at end of file diff --git a/src/hollander_bringup/launch/simulation.launch.py b/src/hollander_bringup/launch/simulation.launch.py index d6155f3..76d7168 100644 --- a/src/hollander_bringup/launch/simulation.launch.py +++ b/src/hollander_bringup/launch/simulation.launch.py @@ -1,25 +1,24 @@ import os -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, ExecuteProcess from launch_ros.actions import Node -from launch.substitutions import Command, LaunchConfiguration +from launch import LaunchDescription +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription from ament_index_python.packages import get_package_share_directory +from launch.launch_description_sources import PythonLaunchDescriptionSource def generate_launch_description(): # Get package dirs launch_dir = get_package_share_directory('hollander_bringup') - package_dir = get_package_share_directory('hollander_description') # Default values - default_model_path = os.path.join(package_dir, 'src/description/rollende_hollander.urdf') default_rviz_config_path = os.path.join(launch_dir, 'rviz/urdf_config.rviz') # Parameters configurable_parameters = [ - {'name': 'model', 'default': default_model_path, 'description': 'Absolute path to robot urdf file'}, {'name': 'need_rviz', 'default': 'False', 'description': 'Whether launch or not rviz'}, {'name': 'rvizconfig', 'default': default_rviz_config_path, 'description': 'Absolute path to rviz config file'}, {'name': 'use_sim_time', 'default': 'True', 'description': 'Flag to enable use_sim_time'}, @@ -28,19 +27,12 @@ def generate_launch_description(): def declare_configurable_parameters(parameters): return [DeclareLaunchArgument(param['name'], default_value=param['default'], description=param['description']) for param in parameters] - """ NODES """ - robot_state_publisher_node = Node( - package='robot_state_publisher', - executable='robot_state_publisher', - parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}] - ) - - joint_state_publisher_node = Node( - package='joint_state_publisher', - executable='joint_state_publisher', - name='joint_state_publisher', + description = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('hollander_bringup'), 'launch', 'description.launch.py')), + condition=IfCondition(LaunchConfiguration('need_description')) ) + """ NODES """ rviz_node = Node( package='rviz2', executable='rviz2', @@ -56,21 +48,12 @@ def generate_launch_description(): output='screen' ) - robot_localization_node = Node( - package='robot_localization', - executable='ekf_node', - name='ekf_filter_node', - output='screen', - parameters=[os.path.join(launch_dir, 'config/simulation.ekf.yaml'), {'use_sim_time': LaunchConfiguration('use_sim_time')}] - ) - return LaunchDescription(declare_configurable_parameters(configurable_parameters) + [ ExecuteProcess(cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], output='screen'), - robot_state_publisher_node, - joint_state_publisher_node, + description, + spawn_entity, - robot_localization_node, rviz_node, ]) -- GitLab