Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
dual_ekf_navsat.launch.py
1 # Copyright 2018 Open Source Robotics Foundation, Inc.
2 # Licensed under the Apache License, Version 2.0 (the "License");
3 # you may not use this file except in compliance with the License.
4 # You may obtain a copy of the License at
5 #
6 # http://www.apache.org/licenses/LICENSE-2.0
7 #
8 # Unless required by applicable law or agreed to in writing, software
9 # distributed under the License is distributed on an "AS IS" BASIS,
10 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
11 # See the License for the specific language governing permissions and
12 # limitations under the License.
13 
14 import os
15 
16 from launch import LaunchDescription
17 import launch.actions
18 import launch_ros.actions
19 
20 
21 def generate_launch_description() -> LaunchDescription:
22  launch_dir = os.path.dirname(os.path.realpath(__file__))
23  params_file = os.path.join(launch_dir, 'dual_ekf_navsat_params.yaml')
24  os.environ['FILE_PATH'] = str(launch_dir)
25  return LaunchDescription(
26  [
27  launch.actions.DeclareLaunchArgument(
28  'output_final_position', default_value='false'
29  ),
30  launch.actions.DeclareLaunchArgument(
31  'output_location', default_value='~/dual_ekf_navsat_example_debug.txt'
32  ),
33  launch_ros.actions.Node(
34  package='robot_localization',
35  executable='ekf_node',
36  name='ekf_filter_node_odom',
37  output='screen',
38  parameters=[params_file, {'use_sim_time': True}],
39  remappings=[('odometry/filtered', 'odometry/local')],
40  ),
41  launch_ros.actions.Node(
42  package='robot_localization',
43  executable='ekf_node',
44  name='ekf_filter_node_map',
45  output='screen',
46  parameters=[params_file, {'use_sim_time': True}],
47  remappings=[('odometry/filtered', 'odometry/global')],
48  ),
49  launch_ros.actions.Node(
50  package='robot_localization',
51  executable='navsat_transform_node',
52  name='navsat_transform',
53  output='screen',
54  parameters=[params_file, {'use_sim_time': True}],
55  remappings=[
56  ('imu/data', 'imu/data'),
57  ('gps/fix', 'gps/fix'),
58  ('gps/filtered', 'gps/filtered'),
59  ('odometry/gps', 'odometry/gps'),
60  ('odometry/filtered', 'odometry/global'),
61  ],
62  ),
63  ]
64  )