From f76fc8257ff5bc922faf141c34b5305f4dce9547 Mon Sep 17 00:00:00 2001 From: shayaf84 Date: Sun, 3 Nov 2024 16:45:38 -0500 Subject: [PATCH] Made launch files for ekf_map, ekf_odom, navsat --- urc_localization/config/ekf.yaml | 2 +- urc_localization/launch/ekf.launch.py | 32 +++++++++++++++++++++------ 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/urc_localization/config/ekf.yaml b/urc_localization/config/ekf.yaml index c358bb00..92ee0069 100644 --- a/urc_localization/config/ekf.yaml +++ b/urc_localization/config/ekf.yaml @@ -83,7 +83,7 @@ ekf_filter_node_map: -navsat_transform_node: +navsat_transform: ros__parameters: # Frequency of the main run loop frequency: 30.0 diff --git a/urc_localization/launch/ekf.launch.py b/urc_localization/launch/ekf.launch.py index bfc24d81..d229d037 100644 --- a/urc_localization/launch/ekf.launch.py +++ b/urc_localization/launch/ekf.launch.py @@ -10,16 +10,34 @@ def generate_launch_description(): - ekf = launch_ros.actions.Node( + ekf_map = launch_ros.actions.Node( package="robot_localization", - executable="navsat_transform_node", - name="navsat_transform_node", + executable="ekf_node", + name="ekf_filter_node_map", output="screen", parameters=[ os.path.join( get_package_share_directory("robot_localization"), "params", - "navsat_transform.yaml", + "ekf.yaml", + ) + ], + remappings=[ + ("gps/fix", "/gps/data"), + ("/imu", "/imu/data"), + ], + ) + + ekf_odom = launch_ros.actions.Node( + package="robot_localization", + executable="ekf_node", + name="ekf_filter_node_odoom", + output="screen", + parameters=[ + os.path.join( + get_package_share_directory("robot_localization"), + "params", + "ekf.yaml", ) ], remappings=[ @@ -30,8 +48,8 @@ def generate_launch_description(): navsat = launch_ros.actions.Node( package="robot_localization", - executable="ekf_node", - name="ekf_filter_node", + executable="navsat_transform_node", + name="navsat_transform", output="screen", parameters=[ os.path.join( @@ -47,7 +65,7 @@ def generate_launch_description(): RegisterEventHandler( event_handler = OnProcessStart( target_action = navsat, - on_start=[ekf] + on_start=[ekf_map,ekf_odom] ) ),