From d16a48e351dd038b06ec1371147118f59e9a5fef Mon Sep 17 00:00:00 2001 From: deathstar Date: Wed, 11 Dec 2024 08:24:13 -0700 Subject: [PATCH] Hearbeat throttle and estimation launch --- mars_ws/src/heartbeat/heartbeat/HeartbeatBase.py | 2 +- mars_ws/src/odometry/launch/estimation_launch.py | 4 ++++ mars_ws/src/odometry/package.xml | 1 - 3 files changed, 5 insertions(+), 2 deletions(-) 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