feat: night mode (Issue #444) #451
@ -0,0 +1,88 @@
|
||||
# Night Mode Configuration
|
||||
|
||||
# Light sensor thresholds
|
||||
light_sensor:
|
||||
threshold_lux: 50 # Lux threshold for auto night mode
|
||||
hysteresis: 5 # Hysteresis to prevent flickering (lux)
|
||||
smoothing_window: 5 # Number of samples to smooth over
|
||||
|
||||
# Sensor sources (priority order)
|
||||
sources:
|
||||
- realsense_ir # RealSense IR intensity
|
||||
- phone_ambient # Phone ambient light sensor
|
||||
- camera_brightness # Fallback: camera frame brightness
|
||||
|
||||
# Night mode parameters
|
||||
night_mode:
|
||||
enabled: true
|
||||
motor_speed_percent: 50 # Reduce motor speed to 50%
|
||||
disable_tts: true # Disable speaker TTS (face only)
|
||||
led_brightness_percent: 5 # Minimum LED brightness
|
||||
face_brightness_percent: 30 # Reduce face display brightness
|
||||
ir_tracking_only: true # Use IR-based tracking only
|
||||
|
||||
# Stealth LED pattern
|
||||
stealth_led:
|
||||
color: [0, 20, 80] # Dim blue RGB
|
||||
pattern: "slow_dim" # Slow breathing pattern
|
||||
speed: 0.3 # Very slow animation (cycles/sec)
|
||||
enabled: true
|
||||
|
||||
# Manual overrides
|
||||
overrides:
|
||||
voice_control: true # Allow voice commands to toggle mode
|
||||
gamepad_control: true # Allow gamepad button to toggle mode
|
||||
gamepad_button: "y" # Gamepad button for toggle (x, y, a, b)
|
||||
|
||||
# Face control
|
||||
face:
|
||||
display_only_in_night: true # Show face in night mode instead of speaker
|
||||
brightness_reduction: 0.3 # Scale brightness to 30%
|
||||
contrast_boost: true # Increase contrast for visibility
|
||||
|
||||
# Motor control
|
||||
motors:
|
||||
night_mode_speed_reduction: 0.5 # 50% of normal speed
|
||||
acceleration_limit: 1.0 # Smooth acceleration in night mode
|
||||
deceleration_limit: 0.8 # Conservative braking
|
||||
|
||||
# TTS control
|
||||
tts:
|
||||
disabled_in_night: true
|
||||
fallback_to_face: true # Show text on face instead
|
||||
volume_in_night: 0 # Muted in night mode
|
||||
|
||||
# Tracking parameters
|
||||
tracking:
|
||||
ir_only: true # Use IR cameras for tracking
|
||||
disable_rgb: true # Don't use RGB cameras
|
||||
ir_sensitivity: 0.8 # IR detection sensitivity
|
||||
tracking_confidence: 0.6 # Minimum tracking confidence
|
||||
|
||||
# Detection ranges
|
||||
detection:
|
||||
detection_range: 5.0 # Meters
|
||||
tracking_range: 3.0 # Meters (closer in IR mode)
|
||||
ir_range_boost: 1.2 # Boost range with IR (x1.2)
|
||||
|
||||
# Publishing
|
||||
publications:
|
||||
night_mode_state: "/saltybot/night_mode"
|
||||
motor_override: "/saltybot/motor_speed_override"
|
||||
tts_override: "/saltybot/tts_disable"
|
||||
face_control: "/saltybot/face_control"
|
||||
led_override: "/saltybot/led_brightness_override"
|
||||
|
||||
# Subscriptions
|
||||
subscriptions:
|
||||
light_level: "/saltybot/light_level"
|
||||
realsense_ir: "/camera/ir/image_raw"
|
||||
phone_sensor: "/phone/ambient_light"
|
||||
voice_command: "/saltybot/voice/command"
|
||||
gamepad_input: "/saltybot/gamepad/input"
|
||||
|
||||
# Transition timing
|
||||
transitions:
|
||||
fade_duration: 1.0 # Seconds to fade between modes
|
||||
motor_ramp_time: 2.0 # Seconds to ramp motor speed
|
||||
led_fade_time: 0.5 # Seconds to fade LED brightness
|
||||
@ -0,0 +1,36 @@
|
||||
"""Launch file for Night Mode controller node."""
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from pathlib import Path
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
"""Generate launch description."""
|
||||
package_dir = get_package_share_directory("saltybot_night_mode")
|
||||
config_file = str(Path(package_dir) / "config" / "night_mode_config.yaml")
|
||||
|
||||
# Launch arguments
|
||||
config_arg = DeclareLaunchArgument(
|
||||
"config_file",
|
||||
default_value=config_file,
|
||||
description="Path to night mode configuration file",
|
||||
)
|
||||
|
||||
# Night Mode node
|
||||
night_mode_node = Node(
|
||||
package="saltybot_night_mode",
|
||||
executable="night_mode_node",
|
||||
name="night_mode_controller",
|
||||
parameters=[
|
||||
{
|
||||
"config_file": LaunchConfiguration("config_file"),
|
||||
}
|
||||
],
|
||||
output="screen",
|
||||
)
|
||||
|
||||
return LaunchDescription([config_arg, night_mode_node])
|
||||
28
jetson/ros2_ws/src/saltybot_night_mode/package.xml
Normal file
28
jetson/ros2_ws/src/saltybot_night_mode/package.xml
Normal file
@ -0,0 +1,28 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>saltybot_night_mode</name>
|
||||
<version>0.1.0</version>
|
||||
<description>
|
||||
Night mode controller for SaltyBot. Detects ambient light from sensors and
|
||||
automatically switches to stealth mode with reduced motor speed, IR tracking,
|
||||
dimmed LEDs, and face-only TTS. Includes manual override via voice/gamepad.
|
||||
</description>
|
||||
<maintainer email="sl-mechanical@saltylab.local">sl-mechanical</maintainer>
|
||||
<license>MIT</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>sensor_msgs</depend>
|
||||
|
||||
<buildtool_depend>ament_python</buildtool_depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
<test_depend>ament_pep257</test_depend>
|
||||
<test_depend>python3-pytest</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_python</build_type>
|
||||
</export>
|
||||
</package>
|
||||
@ -0,0 +1,395 @@
|
||||
#!/usr/bin/env python3
|
||||
"""Night Mode Controller for SaltyBot.
|
||||
|
||||
Detects ambient light from RealSense IR or phone sensors and automatically
|
||||
switches to stealth mode with reduced motor speed, IR tracking, dimmed LEDs,
|
||||
and face-only TTS. Supports manual override via voice/gamepad.
|
||||
|
||||
Published topics:
|
||||
/saltybot/night_mode (std_msgs/String) - JSON night mode status
|
||||
/saltybot/motor_speed_override (std_msgs/Float32) - Motor speed scale (0.0-1.0)
|
||||
/saltybot/tts_disable (std_msgs/Bool) - TTS disable flag
|
||||
/saltybot/face_control (std_msgs/String) - Face display settings JSON
|
||||
/saltybot/led_brightness_override (std_msgs/Float32) - LED brightness
|
||||
|
||||
Subscribed topics:
|
||||
/saltybot/light_level (std_msgs/String) - Ambient light level in lux
|
||||
/saltybot/voice/command (std_msgs/String) - Voice commands
|
||||
/saltybot/gamepad/input (std_msgs/String) - Gamepad input
|
||||
"""
|
||||
|
||||
import json
|
||||
import time
|
||||
from collections import deque
|
||||
from dataclasses import dataclass
|
||||
from typing import Dict, Optional, Deque
|
||||
|
||||
import yaml
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from std_msgs.msg import String, Float32, Bool
|
||||
|
||||
|
||||
@dataclass
|
||||
class NightModeState:
|
||||
"""Night mode state information."""
|
||||
active: bool
|
||||
light_level: float # Lux
|
||||
transition_in_progress: bool
|
||||
transition_progress: float # 0.0-1.0
|
||||
manual_override: bool
|
||||
override_mode: Optional[str] # 'night', 'day', or None
|
||||
|
||||
|
||||
class LightSensor:
|
||||
"""Light level sensor aggregator."""
|
||||
|
||||
def __init__(self, smoothing_window: int = 5):
|
||||
"""Initialize light sensor.
|
||||
|
||||
Args:
|
||||
smoothing_window: Number of samples to average
|
||||
"""
|
||||
self.smoothing_window = smoothing_window
|
||||
self.samples: Deque[float] = deque(maxlen=smoothing_window)
|
||||
self.current_light = 1000.0 # Start assuming daytime (high light)
|
||||
|
||||
def update(self, light_level: float):
|
||||
"""Update with new light level reading."""
|
||||
self.samples.append(light_level)
|
||||
self.current_light = sum(self.samples) / len(self.samples)
|
||||
|
||||
def get_light_level(self) -> float:
|
||||
"""Get smoothed light level."""
|
||||
return self.current_light if self.samples else self.current_light
|
||||
|
||||
|
||||
class TransitionManager:
|
||||
"""Manages smooth transitions between night and day modes."""
|
||||
|
||||
def __init__(self, fade_duration: float = 1.0):
|
||||
"""Initialize transition manager.
|
||||
|
||||
Args:
|
||||
fade_duration: Transition duration in seconds
|
||||
"""
|
||||
self.fade_duration = fade_duration
|
||||
self.transition_start = None
|
||||
self.transition_type = None # 'to_night' or 'to_day'
|
||||
|
||||
def start_transition(self, target_mode: str):
|
||||
"""Start a transition to new mode.
|
||||
|
||||
Args:
|
||||
target_mode: 'night' or 'day'
|
||||
"""
|
||||
self.transition_start = time.time()
|
||||
self.transition_type = f"to_{target_mode}"
|
||||
|
||||
def get_progress(self) -> float:
|
||||
"""Get transition progress (0.0-1.0)."""
|
||||
if self.transition_start is None:
|
||||
return 0.0
|
||||
|
||||
elapsed = time.time() - self.transition_start
|
||||
progress = min(1.0, elapsed / self.fade_duration)
|
||||
|
||||
if progress >= 1.0:
|
||||
self.transition_start = None
|
||||
self.transition_type = None
|
||||
|
||||
return progress
|
||||
|
||||
def is_transitioning(self) -> bool:
|
||||
"""Check if transition in progress."""
|
||||
return self.transition_start is not None
|
||||
|
||||
def apply_transition(self, day_value: float, night_value: float) -> float:
|
||||
"""Apply transition interpolation.
|
||||
|
||||
Args:
|
||||
day_value: Value for day mode
|
||||
night_value: Value for night mode
|
||||
|
||||
Returns:
|
||||
Interpolated value
|
||||
"""
|
||||
progress = self.get_progress()
|
||||
if not self.is_transitioning():
|
||||
return night_value if self.transition_type == 'to_night' else day_value
|
||||
|
||||
if 'night' in self.transition_type:
|
||||
return day_value + (night_value - day_value) * progress
|
||||
else:
|
||||
return night_value + (day_value - night_value) * progress
|
||||
|
||||
|
||||
class NightModeNode(Node):
|
||||
"""ROS2 node for night mode control."""
|
||||
|
||||
def __init__(self):
|
||||
super().__init__("night_mode_controller")
|
||||
|
||||
# Load config
|
||||
self.declare_parameter("config_file", "night_mode_config.yaml")
|
||||
config_path = self.get_parameter("config_file").value
|
||||
self.config = self._load_config(config_path)
|
||||
|
||||
# State tracking
|
||||
self.light_sensor = LightSensor(
|
||||
self.config["light_sensor"]["smoothing_window"]
|
||||
)
|
||||
self.transition_mgr = TransitionManager(
|
||||
self.config["transitions"]["fade_duration"]
|
||||
)
|
||||
self.night_mode_active = False
|
||||
self.manual_override = False
|
||||
self.override_target = None
|
||||
self.last_update = time.time()
|
||||
|
||||
# Subscribers
|
||||
self.create_subscription(String, "/saltybot/light_level", self._light_cb, 10)
|
||||
self.create_subscription(String, "/saltybot/voice/command", self._voice_cb, 10)
|
||||
self.create_subscription(String, "/saltybot/gamepad/input", self._gamepad_cb, 10)
|
||||
|
||||
# Publishers
|
||||
self.night_mode_pub = self.create_publisher(
|
||||
String, "/saltybot/night_mode", 10
|
||||
)
|
||||
self.motor_override_pub = self.create_publisher(
|
||||
Float32, "/saltybot/motor_speed_override", 10
|
||||
)
|
||||
self.tts_disable_pub = self.create_publisher(
|
||||
Bool, "/saltybot/tts_disable", 10
|
||||
)
|
||||
self.face_control_pub = self.create_publisher(
|
||||
String, "/saltybot/face_control", 10
|
||||
)
|
||||
self.led_override_pub = self.create_publisher(
|
||||
Float32, "/saltybot/led_brightness_override", 10
|
||||
)
|
||||
|
||||
# Timer for main loop
|
||||
self.timer = self.create_timer(0.1, self._update_night_mode)
|
||||
|
||||
self.get_logger().info("Night Mode Controller initialized")
|
||||
|
||||
def _load_config(self, config_path: str) -> Dict:
|
||||
"""Load YAML configuration."""
|
||||
try:
|
||||
with open(config_path) as f:
|
||||
return yaml.safe_load(f)
|
||||
except FileNotFoundError:
|
||||
self.get_logger().warn(f"Config not found: {config_path}")
|
||||
return self._default_config()
|
||||
|
||||
def _default_config(self) -> Dict:
|
||||
"""Return default configuration."""
|
||||
return {
|
||||
"light_sensor": {
|
||||
"threshold_lux": 50,
|
||||
"hysteresis": 5,
|
||||
"smoothing_window": 5,
|
||||
},
|
||||
"night_mode": {
|
||||
"enabled": True,
|
||||
"motor_speed_percent": 50,
|
||||
"disable_tts": True,
|
||||
"led_brightness_percent": 5,
|
||||
"face_brightness_percent": 30,
|
||||
"ir_tracking_only": True,
|
||||
"stealth_led": {
|
||||
"color": [0, 20, 80],
|
||||
"pattern": "slow_dim",
|
||||
"speed": 0.3,
|
||||
"enabled": True,
|
||||
},
|
||||
},
|
||||
"overrides": {
|
||||
"voice_control": True,
|
||||
"gamepad_control": True,
|
||||
"gamepad_button": "y",
|
||||
},
|
||||
"transitions": {
|
||||
"fade_duration": 1.0,
|
||||
"motor_ramp_time": 2.0,
|
||||
"led_fade_time": 0.5,
|
||||
},
|
||||
"publications": {
|
||||
"night_mode_state": "/saltybot/night_mode",
|
||||
"motor_override": "/saltybot/motor_speed_override",
|
||||
"tts_override": "/saltybot/tts_disable",
|
||||
"face_control": "/saltybot/face_control",
|
||||
"led_override": "/saltybot/led_brightness_override",
|
||||
},
|
||||
}
|
||||
|
||||
def _light_cb(self, msg: String):
|
||||
"""Handle light level sensor data."""
|
||||
try:
|
||||
data = json.loads(msg.data)
|
||||
light_level = data.get("lux", 1000.0)
|
||||
self.light_sensor.update(light_level)
|
||||
except (json.JSONDecodeError, KeyError):
|
||||
pass
|
||||
|
||||
def _voice_cb(self, msg: String):
|
||||
"""Handle voice commands for manual override."""
|
||||
try:
|
||||
data = json.loads(msg.data)
|
||||
command = data.get("command", "").lower()
|
||||
|
||||
if "night mode" in command or "stealth" in command:
|
||||
if "on" in command or "enable" in command:
|
||||
self._set_manual_override("night")
|
||||
elif "off" in command or "disable" in command:
|
||||
self._set_manual_override("day")
|
||||
elif "toggle" in command:
|
||||
self._toggle_manual_override()
|
||||
except json.JSONDecodeError:
|
||||
pass
|
||||
|
||||
def _gamepad_cb(self, msg: String):
|
||||
"""Handle gamepad input for manual override."""
|
||||
try:
|
||||
data = json.loads(msg.data)
|
||||
button = data.get("button", "")
|
||||
pressed = data.get("pressed", False)
|
||||
|
||||
if button == self.config["overrides"]["gamepad_button"] and pressed:
|
||||
self._toggle_manual_override()
|
||||
except json.JSONDecodeError:
|
||||
pass
|
||||
|
||||
def _set_manual_override(self, mode: str):
|
||||
"""Set manual mode override.
|
||||
|
||||
Args:
|
||||
mode: 'night', 'day', or None for auto
|
||||
"""
|
||||
if mode in ["night", "day"]:
|
||||
self.manual_override = True
|
||||
self.override_target = mode
|
||||
self.get_logger().info(f"Manual override: {mode} mode")
|
||||
else:
|
||||
self.manual_override = False
|
||||
self.override_target = None
|
||||
self.get_logger().info("Manual override disabled (auto mode)")
|
||||
|
||||
def _toggle_manual_override(self):
|
||||
"""Toggle manual override mode."""
|
||||
if not self.manual_override:
|
||||
self._set_manual_override("night" if not self.night_mode_active else "day")
|
||||
else:
|
||||
self._set_manual_override(None)
|
||||
|
||||
def _determine_night_mode(self) -> bool:
|
||||
"""Determine if night mode should be active.
|
||||
|
||||
Returns:
|
||||
True if night mode should be active, False otherwise
|
||||
"""
|
||||
if self.manual_override:
|
||||
return self.override_target == "night"
|
||||
|
||||
light_level = self.light_sensor.get_light_level()
|
||||
threshold = self.config["light_sensor"]["threshold_lux"]
|
||||
hysteresis = self.config["light_sensor"]["hysteresis"]
|
||||
|
||||
if self.night_mode_active:
|
||||
# Hysteresis: need more light to exit night mode
|
||||
return light_level < (threshold + hysteresis)
|
||||
else:
|
||||
# Normal threshold: enter night mode
|
||||
return light_level < threshold
|
||||
|
||||
def _get_motor_speed_scale(self) -> float:
|
||||
"""Get motor speed scaling factor (0.0-1.0)."""
|
||||
if not self.night_mode_active:
|
||||
return 1.0
|
||||
|
||||
target_speed = self.config["night_mode"]["motor_speed_percent"] / 100.0
|
||||
|
||||
if self.transition_mgr.is_transitioning():
|
||||
return self.transition_mgr.apply_transition(1.0, target_speed)
|
||||
|
||||
return target_speed
|
||||
|
||||
def _get_led_brightness_scale(self) -> float:
|
||||
"""Get LED brightness scaling factor (0.0-1.0)."""
|
||||
if not self.night_mode_active:
|
||||
return 1.0
|
||||
|
||||
target_brightness = self.config["night_mode"]["led_brightness_percent"] / 100.0
|
||||
|
||||
if self.transition_mgr.is_transitioning():
|
||||
return self.transition_mgr.apply_transition(1.0, target_brightness)
|
||||
|
||||
return target_brightness
|
||||
|
||||
def _get_face_brightness_scale(self) -> float:
|
||||
"""Get face brightness scaling factor (0.0-1.0)."""
|
||||
if not self.night_mode_active:
|
||||
return 1.0
|
||||
|
||||
target_brightness = self.config["night_mode"]["face_brightness_percent"] / 100.0
|
||||
|
||||
if self.transition_mgr.is_transitioning():
|
||||
return self.transition_mgr.apply_transition(1.0, target_brightness)
|
||||
|
||||
return target_brightness
|
||||
|
||||
def _update_night_mode(self):
|
||||
"""Update night mode state and publish overrides."""
|
||||
# Determine mode
|
||||
should_be_night = self._determine_night_mode()
|
||||
|
||||
# Handle mode transition
|
||||
if should_be_night != self.night_mode_active:
|
||||
self.night_mode_active = should_be_night
|
||||
target = "night" if should_be_night else "day"
|
||||
self.transition_mgr.start_transition(target)
|
||||
self.get_logger().info(f"Night mode: {should_be_night}")
|
||||
|
||||
# Publish night mode state
|
||||
state = {
|
||||
"active": self.night_mode_active,
|
||||
"light_level": round(self.light_sensor.get_light_level(), 1),
|
||||
"transitioning": self.transition_mgr.is_transitioning(),
|
||||
"manual_override": self.manual_override,
|
||||
"threshold_lux": self.config["light_sensor"]["threshold_lux"],
|
||||
}
|
||||
self.night_mode_pub.publish(String(data=json.dumps(state)))
|
||||
|
||||
# Publish motor speed override
|
||||
motor_scale = self._get_motor_speed_scale()
|
||||
self.motor_override_pub.publish(Float32(data=motor_scale))
|
||||
|
||||
# Publish TTS disable
|
||||
tts_disabled = self.night_mode_active and self.config["night_mode"]["disable_tts"]
|
||||
self.tts_disable_pub.publish(Bool(data=tts_disabled))
|
||||
|
||||
# Publish face control settings
|
||||
face_config = {
|
||||
"display_only": self.night_mode_active,
|
||||
"brightness_scale": self._get_face_brightness_scale(),
|
||||
"contrast_boost": self.night_mode_active,
|
||||
}
|
||||
self.face_control_pub.publish(String(data=json.dumps(face_config)))
|
||||
|
||||
# Publish LED brightness override
|
||||
led_scale = self._get_led_brightness_scale()
|
||||
self.led_override_pub.publish(Float32(data=led_scale))
|
||||
|
||||
|
||||
def main(args=None):
|
||||
"""Main entry point."""
|
||||
rclpy.init(args=args)
|
||||
node = NightModeNode()
|
||||
rclpy.spin(node)
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
4
jetson/ros2_ws/src/saltybot_night_mode/setup.cfg
Normal file
4
jetson/ros2_ws/src/saltybot_night_mode/setup.cfg
Normal file
@ -0,0 +1,4 @@
|
||||
[develop]
|
||||
script_dir=$base/lib/saltybot_night_mode
|
||||
[bdist_wheel]
|
||||
universal=0
|
||||
30
jetson/ros2_ws/src/saltybot_night_mode/setup.py
Normal file
30
jetson/ros2_ws/src/saltybot_night_mode/setup.py
Normal file
@ -0,0 +1,30 @@
|
||||
from setuptools import setup
|
||||
|
||||
package_name = "saltybot_night_mode"
|
||||
|
||||
setup(
|
||||
name=package_name,
|
||||
version="0.1.0",
|
||||
packages=[package_name],
|
||||
data_files=[
|
||||
("share/ament_index/resource_index/packages", [f"resource/{package_name}"]),
|
||||
(f"share/{package_name}", ["package.xml"]),
|
||||
(f"share/{package_name}/launch", ["launch/night_mode.launch.py"]),
|
||||
(f"share/{package_name}/config", ["config/night_mode_config.yaml"]),
|
||||
],
|
||||
install_requires=["setuptools", "pyyaml"],
|
||||
zip_safe=True,
|
||||
maintainer="sl-mechanical",
|
||||
maintainer_email="sl-mechanical@saltylab.local",
|
||||
description=(
|
||||
"Night mode controller: IR perception, motor speed reduction, "
|
||||
"stealth LED, TTS disable, face-only mode"
|
||||
),
|
||||
license="MIT",
|
||||
tests_require=["pytest"],
|
||||
entry_points={
|
||||
"console_scripts": [
|
||||
"night_mode_node = saltybot_night_mode.night_mode_node:main",
|
||||
],
|
||||
},
|
||||
)
|
||||
Loading…
x
Reference in New Issue
Block a user