New saltybot_thermal package with thermal_node: reads all /sys/class/thermal/thermal_zone* sysfs entries (millidegrees→°C), publishes /saltybot/thermal JSON at 1 Hz with zones[], max_temp_c, warn, and throttled flags. Logs ROS2 WARN at ≥75°C, ERROR at ≥85°C. thermal_root param allows sysfs override for offline testing. 50/50 tests passing. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
43 lines
1.5 KiB
Python
43 lines
1.5 KiB
Python
"""thermal.launch.py — Launch the Jetson thermal monitor (Issue #205).
|
|
|
|
Usage:
|
|
ros2 launch saltybot_thermal thermal.launch.py
|
|
ros2 launch saltybot_thermal thermal.launch.py warn_temp_c:=70.0
|
|
"""
|
|
|
|
import os
|
|
from ament_index_python.packages import get_package_share_directory
|
|
from launch import LaunchDescription
|
|
from launch.actions import DeclareLaunchArgument
|
|
from launch.substitutions import LaunchConfiguration
|
|
from launch_ros.actions import Node
|
|
|
|
|
|
def generate_launch_description():
|
|
pkg = get_package_share_directory("saltybot_thermal")
|
|
cfg = os.path.join(pkg, "config", "thermal_params.yaml")
|
|
|
|
return LaunchDescription([
|
|
DeclareLaunchArgument("publish_rate_hz", default_value="1.0",
|
|
description="Publish rate (Hz)"),
|
|
DeclareLaunchArgument("warn_temp_c", default_value="75.0",
|
|
description="WARN threshold (°C)"),
|
|
DeclareLaunchArgument("throttle_temp_c", default_value="85.0",
|
|
description="THROTTLE threshold (°C)"),
|
|
|
|
Node(
|
|
package="saltybot_thermal",
|
|
executable="thermal_node",
|
|
name="thermal_node",
|
|
output="screen",
|
|
parameters=[
|
|
cfg,
|
|
{
|
|
"publish_rate_hz": LaunchConfiguration("publish_rate_hz"),
|
|
"warn_temp_c": LaunchConfiguration("warn_temp_c"),
|
|
"throttle_temp_c": LaunchConfiguration("throttle_temp_c"),
|
|
},
|
|
],
|
|
),
|
|
])
|