diff --git a/mars_ws/src/heartbeat/heartbeat/HeartbeatBase.py b/mars_ws/src/heartbeat/heartbeat/HeartbeatBase.py
index 3fc46f8..ad63266 100644
--- a/mars_ws/src/heartbeat/heartbeat/HeartbeatBase.py
+++ b/mars_ws/src/heartbeat/heartbeat/HeartbeatBase.py
@@ -44,7 +44,7 @@ def check_status(self):
if (t - self.startup_time).nanoseconds / 1e9 < p.BASE_HEARTBEAT_WARMUP:
return
if (t - self.last_received).nanoseconds / 1e9 > p.BASE_WARNING_TOLERANCE:
- self.get_logger().warn(p.BASE_WARNING_STRING)
+ self.get_logger().warn(p.BASE_WARNING_STRING, throttle_duration_sec=5)
def main(args=None):
diff --git a/mars_ws/src/odometry/launch/estimation_launch.py b/mars_ws/src/odometry/launch/estimation_launch.py
index 66987f5..a05d6a5 100755
--- a/mars_ws/src/odometry/launch/estimation_launch.py
+++ b/mars_ws/src/odometry/launch/estimation_launch.py
@@ -55,6 +55,10 @@ def generate_launch_description():
executable='imu_filter_madgwick_node',
name='imu_filter_madgwick',
output='screen',
+ remappings=[
+ ('imu/data', 'zed/imu/data'),
+ ('imuu/mag', 'zed/imu/mag')
+ ],
parameters=[imu_config]
),
])
\ No newline at end of file
diff --git a/mars_ws/src/odometry/package.xml b/mars_ws/src/odometry/package.xml
index 2a95f42..5a00bed 100755
--- a/mars_ws/src/odometry/package.xml
+++ b/mars_ws/src/odometry/package.xml
@@ -27,7 +27,6 @@
nav_msgs
std_msgs
ros2launch
- robot_localization
ament_copyright
ament_flake8