Skip to content

Commit

Permalink
local ekf working (odom -> base_link transform
Browse files Browse the repository at this point in the history
  • Loading branch information
mrinalTheCoder committed Dec 12, 2024
1 parent 29ed484 commit d30a2f5
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 20 deletions.
10 changes: 5 additions & 5 deletions urc_localization/config/ekf.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,18 +14,18 @@ ekf_filter_node_odom:
world_frame: odom

imu0: /imu/data
imu0_config: [true, true, false,
imu0_config: [false, false, false,
false, false, true,
true, true, false,
false, false, false,
false, false, true,
true, true, false]
imu0_differential: true
imu0_differential: false
imu0_relative: false
imu0_queue_size: 10
imu_remove_gravitational_acceleration: false

odom0: /rover_drivetrain_controller/odom
odom0_config: [true, true, false,
odom0_config: [false, false, false,
false, false, true,
true, true, false,
false, false, false,
Expand Down Expand Up @@ -173,7 +173,7 @@ navsat_transform:
# Delay time, in seconds, before we calculate the transform from the UTM frame to your world frame.
delay: 2.0
magnetic_declination_radians: -0.06736971
yaw_offset: 1.57079632679
yaw_offset: 0.0
zero_altitude: true
broadcast_utm_transform: true
publish_filtered_gps: true
Expand Down
34 changes: 19 additions & 15 deletions urc_localization/launch/ekf.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

def generate_launch_description():

ekf_map = launch_ros.actions.Node(
ekf_global = launch_ros.actions.Node(
package="robot_localization",
executable="ekf_node",
name="ekf_filter_node_map",
Expand All @@ -23,11 +23,11 @@ def generate_launch_description():
)
],
remappings=[
("/odometry/filtered","/odometry/filtered_map")
("/odometry/filtered","/odometry/filtered_global")
],
)

ekf_odom = launch_ros.actions.Node(
ekf_local = launch_ros.actions.Node(
package="robot_localization",
executable="ekf_node",
name="ekf_filter_node_odom",
Expand All @@ -41,7 +41,7 @@ def generate_launch_description():
],
remappings=[

("/odometry/filtered","odometry/filtered_twist")
("/odometry/filtered","odometry/filtered_local")
],
)

Expand All @@ -59,22 +59,26 @@ def generate_launch_description():
],
remappings=[
("/imu","/imu/data"),
("/odometry/filtered","/odometry/filtered_twist"),
("/odometry/filtered","/odometry/filtered_global"),
("/gps/fix","/gps/data")
]
)

return LaunchDescription(
# [
# RegisterEventHandler(
# event_handler = OnProcessStart(
# target_action = navsat,
# on_start=[ekf_map,ekf_odom]
# )
# ),
# #ekf,
# navsat
#
# ]
[
RegisterEventHandler(
event_handler = OnProcessStart(
target_action = navsat,
on_start=[ekf_map,ekf_odom]

)
),
#ekf,
navsat

navsat,
ekf_local,
ekf_global
]
)

0 comments on commit d30a2f5

Please sign in to comment.