diff --git a/jetson/config/RECOVERY_BEHAVIORS.md b/jetson/config/RECOVERY_BEHAVIORS.md index 14746ca..8ea4d4c 100644 --- a/jetson/config/RECOVERY_BEHAVIORS.md +++ b/jetson/config/RECOVERY_BEHAVIORS.md @@ -4,7 +4,12 @@ ## Overview -Recovery behaviors are triggered when Nav2 encounters navigation failures (path following failures, stuck detection, etc.). The recovery system attempts multiple strategies before giving up. +Recovery behaviors are triggered when Nav2 encounters navigation failures (path following failures, stuck detection, etc.). The recovery system attempts multiple strategies before giving up: + +1. **Clear costmaps** — Reset perception obstacles +2. **Spin recovery** — In-place 90° rotation to detect surroundings +3. **Wait recovery** — 5-second pause for dynamic obstacles to move +4. **Backup recovery** — Reverse 0.3m to escape deadlocks ## Configuration Details @@ -32,13 +37,29 @@ Recovery behaviors are triggered when Nav2 encounters navigation failures (path ## Safety: E-Stop Priority (Issue #459) -The emergency stop system (Issue #459, `saltybot_emergency` package) runs independently of Nav2 and takes absolute priority. +The emergency stop system (Issue #459, `saltybot_emergency` package) runs independently of Nav2 and takes absolute priority: + +- **Trigger**: Obstacles within 0.3m (configurable) +- **Action**: Immediate zero velocity command, overrides all recovery behaviors +- **Integration**: Publishes directly to `/cmd_vel`, pre-empting Nav2 output Recovery behaviors cannot interfere with E-stop because the emergency system operates at the motor driver level on the STM32 firmware. ## Behavior Tree Sequence -Recovery runs in a round-robin fashion with up to 6 retry cycles. +Recovery runs in a round-robin fashion with up to 6 retry cycles: + +``` +NavigateRecovery (6 retries) +├── Normal navigation (compute path → follow path) +└── Recovery fallback: + ├── Clear costmaps + ├── Spin 90° + ├── Wait 5s + └── Back up 0.3m @ 0.1 m/s +``` + +Each cycle, the next recovery action is attempted (round-robin). If navigation succeeds, recovery stops. If all retries exhaust, goal fails. ## Constraints for FC + Hoverboard ESC @@ -49,3 +70,31 @@ This configuration is specifically tuned for: - **Recovery velocity constraints**: 50% of normal for stability The conservative recovery speeds ensure smooth deceleration profiles on the self-balancing drivetrain without tipping or oscillation. + +## Configuration Files + +- **nav2_params.yaml**: behavior_server section with spin, backup, wait parameters +- **navigate_to_pose_with_recovery.xml**: Behavior tree defining recovery sequence +- **emergency.launch.py**: E-stop system (independent, higher priority) + +## Testing + +To test recovery behaviors: + +```bash +# Run Nav2 with recovery enabled +ros2 launch saltybot_bringup nav2.launch.py + +# Trigger recovery by creating obstacles in the path +# or setting unreachable goals + +# Monitor recovery with: +ros2 topic echo /cmd_vel # Check velocity commands during recovery +ros2 topic echo /diagnostics # Monitor Nav2 status +``` + +## References + +- Issue #479: Nav2 recovery behaviors +- Issue #459: Emergency stop cascade (E-stop takes priority) +- Nav2 recovery behavior documentation: https://docs.nav2.org/ diff --git a/jetson/config/nav2_params.yaml b/jetson/config/nav2_params.yaml index dd774d3..efcb0d9 100644 --- a/jetson/config/nav2_params.yaml +++ b/jetson/config/nav2_params.yaml @@ -103,8 +103,8 @@ controller_server: progress_checker: plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 - movement_time_allowance: 10.0 + required_movement_radius: 0.2 # Issue #479: Minimum 20cm movement to detect progress + movement_time_allowance: 10.0 # 10 second window to detect movement, then attempt recovery general_goal_checker: stateful: true @@ -180,6 +180,8 @@ smoother_server: do_refinement: true # ── Behavior Server (recovery behaviors) ──────────────────────────────────── +# Issue #479: Recovery behaviors with conservative speed/distance limits for FC+Hoverboard +# ESC priority: E-stop (Issue #459) takes priority over any recovery behavior. behavior_server: ros__parameters: use_sim_time: false @@ -188,25 +190,40 @@ behavior_server: local_footprint_topic: local_costmap/published_footprint global_footprint_topic: global_costmap/published_footprint cycle_frequency: 10.0 - behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] + behavior_plugins: ["spin", "backup", "wait"] + + # Spin recovery: In-place 90° rotation to escape local deadlock spin: plugin: "nav2_behaviors/Spin" + spin_dist: 1.5708 # 90 degrees (π/2 radians) + max_rotational_vel: 0.5 # Conservative: 0.5 rad/s for self-balancer stability + min_rotational_vel: 0.25 # Minimum angular velocity + rotational_acc_lim: 1.6 # Half of max (3.2) for smooth accel on self-balancer + time_allowance: 10.0 # max 10 seconds to complete 90° rotation + + # Backup recovery: Reverse 0.3m at 0.1 m/s to escape obstacles + # Conservative for FC (Flux Capacitor) + Hoverboard ESC drivetrain backup: plugin: "nav2_behaviors/BackUp" - drive_on_heading: - plugin: "nav2_behaviors/DriveOnHeading" + backup_dist: 0.3 # Reverse 0.3 meters (safe distance for deadlock escape) + backup_speed: 0.1 # Very conservative: 0.1 m/s reverse + max_backup_vel: 0.15 # Absolute max reverse velocity + min_backup_vel: 0.05 # Minimum backup velocity threshold + time_allowance: 5.0 # max 5 seconds (0.3m at 0.1m/s = 3s normal) + + # Wait recovery: Pause 5 seconds to let obstacles move away wait: plugin: "nav2_behaviors/Wait" - assisted_teleop: - plugin: "nav2_behaviors/AssistedTeleop" + wait_duration: 5.0 # 5 second pause + local_frame: odom global_frame: map robot_base_frame: base_link transform_tolerance: 0.1 simulate_ahead_time: 2.0 - max_rotational_vel: 1.0 - min_rotational_vel: 0.4 - rotational_acc_lim: 3.2 + max_rotational_vel: 0.5 # Conservative: self-balancer stability limit + min_rotational_vel: 0.25 + rotational_acc_lim: 1.6 # Half of main limit for recovery behaviors # ── Waypoint Follower ──────────────────────────────────────────────────────── waypoint_follower: diff --git a/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/autonomous_coordinator.xml b/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/autonomous_coordinator.xml new file mode 100644 index 0000000..ea76a5a --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/autonomous_coordinator.xml @@ -0,0 +1,457 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/navigate_to_pose_with_recovery.xml b/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/navigate_to_pose_with_recovery.xml index 369caf6..9c56ca1 100644 --- a/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/navigate_to_pose_with_recovery.xml +++ b/jetson/ros2_ws/src/saltybot_bringup/behavior_trees/navigate_to_pose_with_recovery.xml @@ -3,11 +3,14 @@ navigate_to_pose_with_recovery.xml — SaltyBot Nav2 behavior tree Format: BehaviorTree.CPP v4 (ROS2 Humble) - Recovery sequence (outer RecoveryNode, 6 retries): + Recovery sequence (outer RecoveryNode, 6 retries) — Issue #479: 1. Clear local + global costmaps - 2. Spin 90° (1.57 rad) - 3. Wait 5 s - 4. Back up 0.30 m + 2. Spin 90° in-place (1.57 rad @ 0.5 rad/s) + 3. Wait 5 s (e.g., for obstacles to move away) + 4. Back up 0.30 m at 0.1 m/s (conservative for FC + Hoverboard ESC) + + E-stop (Issue #459) priority: Emergency stop takes priority over recovery behaviors. + Progress checker threshold: 20cm minimum movement within 10s to declare progress. Each recovery runs round-robin until navigation succeeds or retries exhausted. --> @@ -64,8 +67,8 @@ - - + + diff --git a/jetson/ros2_ws/src/saltybot_bringup/config/nav2_params.yaml b/jetson/ros2_ws/src/saltybot_bringup/config/nav2_params.yaml new file mode 100644 index 0000000..daea7bf --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_bringup/config/nav2_params.yaml @@ -0,0 +1,413 @@ +# Nav2 parameters — SaltyBot (Jetson Orin Nano Super / ROS2 Humble) +# +# Robot: differential-drive self-balancing two-wheeler +# robot_radius: 0.15 m (~0.2m with margin) +# footprint: 0.4 x 0.4 m (x 2m for buffer) +# max_vel_x: 1.0 m/s +# max_vel_theta: 1.5 rad/s +# +# Localization: RTAB-Map (publishes /map + map→odom TF + /rtabmap/odom) +# → No AMCL, no map_server needed. +# +# Sensors (Issue #478 — Costmap configuration): +# /scan — RPLIDAR A1M8 360° LaserScan (obstacle layer) +# /depth_scan — RealSense D435i depth_to_laserscan (obstacle layer) +# /camera/depth/color/points — RealSense D435i PointCloud2 (voxel layer, local only) +# +# Inflation: +# inflation_radius: 0.3m (robot_radius 0.15m + 0.15m padding) +# +# Output: /cmd_vel (Twist) — STM32 bridge consumes this topic. + +bt_navigator: + ros__parameters: + use_sim_time: false + global_frame: map + robot_base_frame: base_link + odom_topic: /rtabmap/odom + bt_loop_duration: 10 + default_server_timeout: 20 + wait_for_service_timeout: 1000 + action_server_result_timeout: 900.0 + navigators: ['navigate_to_pose', 'navigate_through_poses'] + navigate_to_pose: + plugin: "nav2_bt_navigator/NavigateToPoseNavigator" + navigate_through_poses: + plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator" + # default_bt_xml_filename is set at launch time via nav2.launch.py + error_code_names: + - compute_path_error_code + - follow_path_error_code + plugin_lib_names: + - nav2_compute_path_to_pose_action_bt_node + - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_action_bt_node + - nav2_assisted_teleop_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_bt_node + - nav2_clear_costmap_service_bt_node + - nav2_is_stuck_condition_bt_node + - nav2_goal_reached_condition_bt_node + - nav2_goal_updated_condition_bt_node + - nav2_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_condition_bt_node + - nav2_initial_pose_received_condition_bt_node + - nav2_reinitialize_global_localization_service_bt_node + - nav2_rate_controller_bt_node + - nav2_distance_controller_bt_node + - nav2_speed_controller_bt_node + - nav2_truncate_path_action_bt_node + - nav2_truncate_path_local_action_bt_node + - nav2_goal_updater_node_bt_node + - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node + - nav2_round_robin_node_bt_node + - nav2_transform_available_condition_bt_node + - nav2_time_expired_condition_bt_node + - nav2_path_expiring_timer_condition + - nav2_distance_traveled_condition_bt_node + - nav2_single_trigger_bt_node + - nav2_goal_updated_controller_bt_node + - nav2_navigate_through_poses_action_bt_node + - nav2_navigate_to_pose_action_bt_node + - nav2_remove_passed_goals_action_bt_node + - nav2_planner_selector_bt_node + - nav2_controller_selector_bt_node + - nav2_goal_checker_selector_bt_node + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_assisted_teleop_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node + +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: false + +bt_navigator_navigate_to_pose_rclcpp_node: + ros__parameters: + use_sim_time: false + +# ── Controller Server (DWB — local trajectory follower) ───────────────────── +controller_server: + ros__parameters: + use_sim_time: false + controller_frequency: 10.0 # Hz — Orin can handle 10Hz easily + min_x_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 # not holonomic — effectively disabled + min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 + progress_checker_plugin: "progress_checker" + goal_checker_plugins: ["general_goal_checker"] + controller_plugins: ["FollowPath"] + + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.2 # Issue #479: Minimum 20cm movement to detect progress + movement_time_allowance: 10.0 # 10 second window to detect movement, then attempt recovery + + general_goal_checker: + stateful: true + plugin: "nav2_controller::SimpleGoalChecker" + xy_goal_tolerance: 0.25 + yaw_goal_tolerance: 0.25 + + FollowPath: + plugin: "dwb_core::DWBLocalPlanner" + debug_trajectory_details: false + # Velocity limits + min_vel_x: -0.25 # allow limited reverse + min_vel_y: 0.0 + max_vel_x: 1.0 + max_vel_y: 0.0 + max_vel_theta: 1.5 + min_speed_xy: 0.0 + max_speed_xy: 1.0 + min_speed_theta: 0.0 + # Acceleration limits (differential drive) + acc_lim_x: 2.5 + acc_lim_y: 0.0 + acc_lim_theta: 3.2 + decel_lim_x: -2.5 + decel_lim_y: 0.0 + decel_lim_theta: -3.2 + # Trajectory sampling + vx_samples: 20 + vy_samples: 5 + vtheta_samples: 20 + sim_time: 1.7 + linear_granularity: 0.05 + angular_granularity: 0.025 + transform_tolerance: 0.2 + xy_goal_tolerance: 0.25 + trans_stopped_velocity: 0.25 + short_circuit_trajectory_evaluation: true + stateful: true + critics: + ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] + BaseObstacle.scale: 0.02 + PathAlign.scale: 32.0 + PathAlign.forward_point_distance: 0.1 + GoalAlign.scale: 24.0 + GoalAlign.forward_point_distance: 0.1 + PathDist.scale: 32.0 + GoalDist.scale: 24.0 + RotateToGoal.scale: 32.0 + RotateToGoal.slowing_factor: 5.0 + RotateToGoal.lookahead_time: -1.0 + +# ── Planner Server (NavFn global path planner) ─────────────────────────────── +planner_server: + ros__parameters: + use_sim_time: false + expected_planner_frequency: 20.0 + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + +# ── Smoother Server ────────────────────────────────────────────────────────── +smoother_server: + ros__parameters: + use_sim_time: false + smoother_plugins: ["simple_smoother"] + simple_smoother: + plugin: "nav2_smoother::SimpleSmoother" + tolerance: 1.0e-10 + max_its: 1000 + do_refinement: true + +# ── Behavior Server (recovery behaviors) ──────────────────────────────────── +# Issue #479: Recovery behaviors with conservative speed/distance limits for FC+Hoverboard +# ESC priority: E-stop (Issue #459) takes priority over any recovery behavior. +behavior_server: + ros__parameters: + use_sim_time: false + local_costmap_topic: local_costmap/costmap_raw + global_costmap_topic: global_costmap/costmap_raw + local_footprint_topic: local_costmap/published_footprint + global_footprint_topic: global_costmap/published_footprint + cycle_frequency: 10.0 + behavior_plugins: ["spin", "backup", "wait"] + + # Spin recovery: In-place 90° rotation to escape local deadlock + spin: + plugin: "nav2_behaviors/Spin" + spin_dist: 1.5708 # 90 degrees (π/2 radians) + max_rotational_vel: 0.5 # Conservative: 0.5 rad/s for self-balancer stability + min_rotational_vel: 0.25 # Minimum angular velocity + rotational_acc_lim: 1.6 # Half of max (3.2) for smooth accel on self-balancer + time_allowance: 10.0 # max 10 seconds to complete 90° rotation + + # Backup recovery: Reverse 0.3m at 0.1 m/s to escape obstacles + # Conservative for FC (Flux Capacitor) + Hoverboard ESC drivetrain + backup: + plugin: "nav2_behaviors/BackUp" + backup_dist: 0.3 # Reverse 0.3 meters (safe distance for deadlock escape) + backup_speed: 0.1 # Very conservative: 0.1 m/s reverse + max_backup_vel: 0.15 # Absolute max reverse velocity + min_backup_vel: 0.05 # Minimum backup velocity threshold + time_allowance: 5.0 # max 5 seconds (0.3m at 0.1m/s = 3s normal) + + # Wait recovery: Pause 5 seconds to let obstacles move away + wait: + plugin: "nav2_behaviors/Wait" + wait_duration: 5.0 # 5 second pause + + local_frame: odom + global_frame: map + robot_base_frame: base_link + transform_tolerance: 0.1 + simulate_ahead_time: 2.0 + max_rotational_vel: 0.5 # Conservative: self-balancer stability limit + min_rotational_vel: 0.25 + rotational_acc_lim: 1.6 # Half of main limit for recovery behaviors + +# ── Waypoint Follower ──────────────────────────────────────────────────────── +waypoint_follower: + ros__parameters: + use_sim_time: false + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: true + waypoint_pause_duration: 200 + +# ── Velocity Smoother ──────────────────────────────────────────────────────── +velocity_smoother: + ros__parameters: + use_sim_time: false + smoothing_frequency: 20.0 + scale_velocities: false + feedback: "OPEN_LOOP" + max_velocity: [1.0, 0.0, 1.5] + min_velocity: [-0.25, 0.0, -1.5] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: /rtabmap/odom + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 + +# ── Local Costmap ──────────────────────────────────────────────────────────── +local_costmap: + local_costmap: + ros__parameters: + use_sim_time: false + update_frequency: 10.0 # Hz — Orin can sustain 10Hz + publish_frequency: 5.0 + global_frame: odom + robot_base_frame: base_link + rolling_window: true + width: 3 + height: 3 + resolution: 0.05 + robot_radius: 0.15 + # Footprint: [x, y] in base_link frame, in counterclockwise order + # Robot footprint ~0.4m x 0.4m, with 2m lookahead buffer for controller stability + footprint: "[[-0.2, -0.2], [-0.2, 0.2], [0.2, 0.2], [0.2, -0.2]]" + plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"] + + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: true + observation_sources: scan surround_cameras + scan: + topic: /scan + max_obstacle_height: 0.80 + clearing: true + marking: true + data_type: "LaserScan" + raytrace_max_range: 8.0 + raytrace_min_range: 0.0 + obstacle_max_range: 7.5 + obstacle_min_range: 0.0 + # 4× IMX219 camera-detected obstacles (chairs, glass, people) + surround_cameras: + topic: /surround_vision/obstacles + min_obstacle_height: 0.05 + max_obstacle_height: 1.50 + clearing: false + marking: true + data_type: "PointCloud2" + raytrace_max_range: 3.5 + raytrace_min_range: 0.0 + obstacle_max_range: 3.0 + obstacle_min_range: 0.0 + + voxel_layer: + plugin: "nav2_costmap_2d::VoxelLayer" + enabled: true + publish_voxel_map: false + origin_z: 0.0 + z_resolution: 0.05 + z_voxels: 16 + max_obstacle_height: 0.80 + mark_threshold: 0 + observation_sources: depth_camera + depth_camera: + topic: /camera/depth/color/points + min_obstacle_height: 0.05 # above floor level + max_obstacle_height: 0.80 + marking: true + clearing: true + data_type: "PointCloud2" + raytrace_max_range: 4.0 + raytrace_min_range: 0.0 + obstacle_max_range: 3.5 + obstacle_min_range: 0.0 + + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.3 # robot_radius (0.15) + 0.15m padding for safety + + always_send_full_costmap: false + +# ── Global Costmap ─────────────────────────────────────────────────────────── +global_costmap: + global_costmap: + ros__parameters: + use_sim_time: false + update_frequency: 5.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: base_link + robot_radius: 0.15 + # Footprint: [x, y] in base_link frame, in counterclockwise order + footprint: "[[-0.2, -0.2], [-0.2, 0.2], [0.2, 0.2], [0.2, -0.2]]" + resolution: 0.05 + track_unknown_space: true + plugins: ["static_layer", "obstacle_layer", "inflation_layer"] + + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: true # for RTAB-Map's transient-local /map + + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: true + # Issue #478: RPLIDAR + RealSense depth_scan + observation_sources: scan depth_scan surround_cameras + scan: + topic: /scan + max_obstacle_height: 0.80 + clearing: true + marking: true + data_type: "LaserScan" + raytrace_max_range: 8.0 + raytrace_min_range: 0.0 + obstacle_max_range: 7.5 + obstacle_min_range: 0.0 + # RealSense D435i depth_to_laserscan (synthetic LaserScan from depth) + depth_scan: + topic: /depth_scan + max_obstacle_height: 0.80 + clearing: true + marking: true + data_type: "LaserScan" + raytrace_max_range: 6.0 + raytrace_min_range: 0.1 + obstacle_max_range: 5.5 + obstacle_min_range: 0.0 + surround_cameras: + topic: /surround_vision/obstacles + min_obstacle_height: 0.05 + max_obstacle_height: 1.50 + clearing: false + marking: true + data_type: "PointCloud2" + raytrace_max_range: 3.5 + raytrace_min_range: 0.0 + obstacle_max_range: 3.0 + obstacle_min_range: 0.0 + + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.3 # robot_radius (0.15) + 0.15m padding for safety + + always_send_full_costmap: false + +# ── Map Server / Map Saver (not used — RTAB-Map provides /map) ─────────────── +map_server: + ros__parameters: + use_sim_time: false + yaml_filename: "" + +map_saver: + ros__parameters: + use_sim_time: false + save_map_timeout: 5.0 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: true diff --git a/jetson/ros2_ws/src/saltybot_bringup/launch/autonomous_mode.launch.py b/jetson/ros2_ws/src/saltybot_bringup/launch/autonomous_mode.launch.py new file mode 100644 index 0000000..3edaa8c --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_bringup/launch/autonomous_mode.launch.py @@ -0,0 +1,178 @@ +""" +autonomous_mode.launch.py — SaltyBot Autonomous Mode Launcher (Issue #482) +Starts the behavior tree coordinator with all required subsystems. +""" + +from launch import LaunchDescription +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch.substitutions import PathJoinSubstitution, LaunchConfiguration +import os + +def generate_launch_description(): + """Generate launch description for autonomous mode.""" + + saltybot_bringup_dir = FindPackageShare('saltybot_bringup') + bt_xml_dir = PathJoinSubstitution([saltybot_bringup_dir, 'behavior_trees']) + + return LaunchDescription([ + + # ──────────────────────────────────────────────────────────────────────── + # Behavior Tree Executor Node (Nav2 BT framework) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_bt_executor', + executable='behavior_tree_executor', + name='autonomous_coordinator', + output='screen', + parameters=[{ + 'bt_xml_filename': PathJoinSubstitution([ + bt_xml_dir, 'autonomous_coordinator.xml' + ]), + 'blackboard_variables': { + 'battery_level': 100.0, + 'person_detected': False, + 'obstacle_state': 'clear', + 'current_mode': 'idle', + 'home_pose': { + 'header': { + 'frame_id': 'map', + 'stamp': {'sec': 0, 'nsec': 0} + }, + 'pose': { + 'position': {'x': 0.0, 'y': 0.0, 'z': 0.0}, + 'orientation': {'x': 0.0, 'y': 0.0, 'z': 0.0, 'w': 1.0} + } + } + }, + 'enable_groot_monitoring': True, + 'groot_port': 5555, + }], + remappings=[ + ('/clicked_point', '/bt/clicked_point'), + ('/goal_pose', '/bt/goal_pose'), + ], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Battery Monitor (publishes to /battery_state for BT) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_battery_monitor', + executable='battery_monitor_node', + name='battery_monitor', + output='screen', + parameters=[{ + 'update_rate': 1.0, # Hz + 'critical_threshold': 10.0, + 'warning_threshold': 20.0, + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Person Detector (publishes detected persons for BT) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_perception', + executable='person_detector', + name='person_detector', + output='screen', + ), + + # ──────────────────────────────────────────────────────────────────────── + # Obstacle Monitor (LIDAR-based obstacle detection) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_lidar_avoidance', + executable='obstacle_monitor', + name='obstacle_monitor', + output='screen', + parameters=[{ + 'danger_distance': 0.3, + 'warning_distance': 0.6, + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Autonomy Mode Manager (handles mode transitions, safety checks) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_mode_switch', + executable='autonomous_mode_manager', + name='autonomous_mode_manager', + output='screen', + parameters=[{ + 'auto_return_battery': 20.0, # Return home if battery < 20% + 'enable_geofence': True, + 'geofence_boundary_distance': 5.0, + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Person Follower (follows detected persons) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_follower', + executable='person_follower', + name='person_follower', + output='screen', + parameters=[{ + 'follow_distance': 1.5, + 'max_linear_vel': 0.5, + 'max_angular_vel': 1.0, + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Curiosity Behavior (autonomous exploration) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_curiosity', + executable='curiosity_explorer', + name='curiosity_explorer', + output='screen', + parameters=[{ + 'exploration_mode': 'active', + 'max_exploration_distance': 2.0, + 'idle_timeout': 60.0, # Start exploration after 60s idle + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Gesture Recognition (for interactive mode) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_gesture_recognition', + executable='gesture_recognition_node', + name='gesture_recognition', + output='screen', + parameters=[{ + 'min_confidence': 0.6, + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # TTS Service (for greetings and social interaction) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_tts_service', + executable='tts_service', + name='tts_service', + output='screen', + parameters=[{ + 'voice_speed': 1.0, + 'voice_pitch': 1.0, + }], + ), + + # ──────────────────────────────────────────────────────────────────────── + # Emergency Stop Monitor (highest priority safety) + # ──────────────────────────────────────────────────────────────────────── + Node( + package='saltybot_emergency_stop', + executable='emergency_stop_monitor', + name='emergency_stop_monitor', + output='screen', + ), + + ]) diff --git a/jetson/ros2_ws/src/saltybot_bringup/test/test_terrain_classifier.py b/jetson/ros2_ws/src/saltybot_bringup/test/test_terrain_classifier.py new file mode 100644 index 0000000..44d5aeb --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_bringup/test/test_terrain_classifier.py @@ -0,0 +1,171 @@ +#!/usr/bin/env python3 +""" +test_terrain_classifier.py — Unit tests for terrain classification logic. + +Tests the core algorithms without requiring ROS2 or hardware. +""" + +import unittest +import numpy as np +from unittest.mock import Mock, patch + +import sys +import os + +sys.path.insert(0, os.path.join(os.path.dirname(__file__), '..')) + +from saltybot_bringup.terrain_classifier_node import ( + IMUVibrationAnalyzer, + CNNTextureAnalyzer, + TerrainClassifier, + TerrainDecision, +) + + +class TestIMUVibrationAnalyzer(unittest.TestCase): + """Test IMU vibration analysis and FFT roughness computation.""" + + def setUp(self): + self.analyzer = IMUVibrationAnalyzer(window_size=100, sample_rate=100.0) + + def test_empty_buffer_returns_zero(self): + roughness, accel_mag = self.analyzer.compute_roughness() + self.assertEqual(roughness, 0.0) + self.assertEqual(accel_mag, 0.0) + + def test_smooth_surface_low_roughness(self): + for _ in range(100): + self.analyzer.add_sample(0.0, 0.0, 0.0) + + roughness, accel_mag = self.analyzer.compute_roughness() + self.assertLess(roughness, 0.2) + + def test_rough_surface_high_roughness(self): + for i in range(100): + vibration = 2.0 * np.sin(2 * np.pi * 20 * i / 100.0) + self.analyzer.add_sample(vibration, vibration, vibration) + + roughness, accel_mag = self.analyzer.compute_roughness() + self.assertGreater(roughness, 0.3) + + def test_buffer_size_respected(self): + self.assertEqual(self.analyzer.accel_buffer.maxlen, 100) + for i in range(150): + self.analyzer.add_sample(i, i, i) + + self.assertEqual(len(self.analyzer.accel_buffer), 100) + + def test_reset_clears_buffer(self): + for i in range(50): + self.analyzer.add_sample(i, i, i) + + self.assertGreater(len(self.analyzer.accel_buffer), 0) + self.analyzer.reset() + self.assertEqual(len(self.analyzer.accel_buffer), 0) + + def test_roughness_is_normalized(self): + for i in range(100): + vibration = 5.0 * np.sin(2 * np.pi * 30 * i / 100.0) + self.analyzer.add_sample(vibration, vibration, vibration) + + roughness, _ = self.analyzer.compute_roughness() + self.assertGreaterEqual(roughness, 0.0) + self.assertLessEqual(roughness, 1.0) + + +class TestTerrainClassifier(unittest.TestCase): + """Test terrain classification decision logic.""" + + def setUp(self): + self.classifier = TerrainClassifier() + + def test_pavement_classification(self): + decision = self.classifier.classify( + imu_roughness=0.1, + accel_magnitude=9.85, + cnn_features=None + ) + + self.assertEqual(decision.terrain_type, self.classifier.TERRAIN_PAVEMENT) + self.assertGreater(decision.confidence, 0.7) + self.assertEqual(decision.recommended_speed_ratio, 1.0) + + def test_grass_classification(self): + decision = self.classifier.classify( + imu_roughness=0.25, + accel_magnitude=9.9, + cnn_features=None + ) + + self.assertEqual(decision.terrain_type, self.classifier.TERRAIN_GRASS) + self.assertGreater(decision.confidence, 0.5) + self.assertEqual(decision.recommended_speed_ratio, 0.8) + + def test_gravel_classification(self): + decision = self.classifier.classify( + imu_roughness=0.55, + accel_magnitude=10.0, + cnn_features=None + ) + + self.assertEqual(decision.terrain_type, self.classifier.TERRAIN_GRAVEL) + self.assertGreater(decision.confidence, 0.5) + self.assertEqual(decision.recommended_speed_ratio, 0.5) + + def test_sand_classification(self): + decision = self.classifier.classify( + imu_roughness=0.6, + accel_magnitude=10.3, + cnn_features=None + ) + + self.assertEqual(decision.terrain_type, self.classifier.TERRAIN_SAND) + self.assertGreater(decision.confidence, 0.5) + self.assertEqual(decision.recommended_speed_ratio, 0.4) + + def test_all_terrains_have_speed_recommendations(self): + for terrain_type in range(6): + self.assertIn( + terrain_type, + self.classifier.SPEED_RECOMMENDATIONS + ) + + speed_ratio = self.classifier.SPEED_RECOMMENDATIONS[terrain_type] + self.assertGreater(speed_ratio, 0.0) + self.assertLessEqual(speed_ratio, 1.0) + + def test_decision_fields_are_valid(self): + decision = self.classifier.classify(0.3, 9.9) + + self.assertGreaterEqual(decision.terrain_type, 0) + self.assertLessEqual(decision.terrain_type, 5) + + self.assertGreaterEqual(decision.roughness, 0.0) + self.assertLessEqual(decision.roughness, 1.0) + + self.assertGreaterEqual(decision.confidence, 0.0) + self.assertLessEqual(decision.confidence, 1.0) + + self.assertGreater(decision.recommended_speed_ratio, 0.0) + self.assertLessEqual(decision.recommended_speed_ratio, 1.0) + + +class TestTerrainDecisionDataclass(unittest.TestCase): + """Test TerrainDecision dataclass.""" + + def test_terrain_decision_creation(self): + decision = TerrainDecision( + terrain_type=1, + roughness=0.3, + confidence=0.8, + recommended_speed_ratio=0.9 + ) + + self.assertEqual(decision.terrain_type, 1) + self.assertEqual(decision.roughness, 0.3) + self.assertEqual(decision.confidence, 0.8) + self.assertEqual(decision.recommended_speed_ratio, 0.9) + + +if __name__ == '__main__': + unittest.main() diff --git a/jetson/ros2_ws/src/saltybot_bringup/urdf/saltybot.urdf.xacro b/jetson/ros2_ws/src/saltybot_bringup/urdf/saltybot.urdf.xacro new file mode 100644 index 0000000..1db61ac --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_bringup/urdf/saltybot.urdf.xacro @@ -0,0 +1,249 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jetson/ros2_ws/src/saltybot_dashboard/.gitignore b/jetson/ros2_ws/src/saltybot_dashboard/.gitignore new file mode 100644 index 0000000..751af27 --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/.gitignore @@ -0,0 +1,8 @@ +build/ +install/ +log/ +*.pyc +__pycache__/ +*.egg-info/ +dist/ +.env diff --git a/jetson/ros2_ws/src/saltybot_dashboard/package.xml b/jetson/ros2_ws/src/saltybot_dashboard/package.xml new file mode 100644 index 0000000..6bc72ff --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/package.xml @@ -0,0 +1,27 @@ + + + + saltybot_dashboard + 0.1.0 + Remote monitoring dashboard for SaltyBot with WebSocket live updates + seb + MIT + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + rclpy + sensor_msgs + std_msgs + nav_msgs + geometry_msgs + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/jetson/ros2_ws/src/saltybot_dashboard/resource/saltybot_dashboard b/jetson/ros2_ws/src/saltybot_dashboard/resource/saltybot_dashboard new file mode 100644 index 0000000..e69de29 diff --git a/jetson/ros2_ws/src/saltybot_dashboard/saltybot_dashboard/__init__.py b/jetson/ros2_ws/src/saltybot_dashboard/saltybot_dashboard/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/jetson/ros2_ws/src/saltybot_dashboard/saltybot_dashboard/dashboard_node.py b/jetson/ros2_ws/src/saltybot_dashboard/saltybot_dashboard/dashboard_node.py new file mode 100644 index 0000000..b9e46df --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/saltybot_dashboard/dashboard_node.py @@ -0,0 +1,200 @@ +#!/usr/bin/env python3 +""" +Remote monitoring dashboard for SaltyBot — web UI on Orin port 8080. + +Displays: +- Battery %, current state +- Sensor health (audio, vision, lidar) +- Map view (occupancy grid) +- Event log (last 20 from event logger #473) +- Motor speeds +- WiFi signal strength + +WebSocket updates push data in real-time to connected clients. +""" + +import rclpy +from rclpy.node import Node +from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy +from std_msgs.msg import String, Float32 +from sensor_msgs.msg import Image, BatteryState +from nav_msgs.msg import OccupancyGrid +import json +import time +from collections import deque +from threading import Thread +from flask import Flask, render_template, jsonify +from flask_socketio import SocketIO, emit, disconnect + +_SENSOR_QOS = QoSProfile( + reliability=ReliabilityPolicy.BEST_EFFORT, + history=HistoryPolicy.KEEP_LAST, + depth=5, +) + + +class DashboardNode(Node): + def __init__(self): + super().__init__('dashboard_node') + + # State + self.battery_percent = 100.0 + self.battery_voltage = 0.0 + self.robot_state = "IDLE" + self.motor_speeds = {"left": 0.0, "right": 0.0} + self.wifi_signal = -50 + self.sensor_health = { + "camera": True, + "lidar": True, + "audio": True, + "imu": True, + } + self.event_log = deque(maxlen=20) + self.map_data = None + self.last_update = time.time() + + # Global Flask app reference for socketio + global socketio_instance + socketio_instance = None + + # Subscribers + self.create_subscription(Float32, '/saltybot/battery_percent', self.battery_callback, 10) + self.create_subscription(BatteryState, '/saltybot/battery_state', self.battery_state_callback, 10) + self.create_subscription(String, '/saltybot/telemetry/motor_rpm', self.motor_callback, 10) + self.create_subscription(String, '/saltybot/state', self.state_callback, 10) + self.create_subscription(String, '/saltybot/events', self.event_callback, 10) + self.create_subscription(OccupancyGrid, '/map', self.map_callback, _SENSOR_QOS) + self.create_subscription(String, '/saltybot/sensor_health', self.sensor_health_callback, 10) + + # Update timer for periodic broadcasts + self.timer = self.create_timer(0.5, self.broadcast_update) + + self.get_logger().info("Dashboard node initialized on port 8080") + + def battery_callback(self, msg): + self.battery_percent = msg.data + + def battery_state_callback(self, msg): + if hasattr(msg, 'voltage'): + self.battery_voltage = msg.voltage + + def motor_callback(self, msg): + try: + data = json.loads(msg.data) + if 'left' in data and 'right' in data: + self.motor_speeds = {"left": float(data['left']), "right": float(data['right'])} + except (json.JSONDecodeError, ValueError, KeyError): + pass + + def state_callback(self, msg): + self.robot_state = msg.data + + def event_callback(self, msg): + try: + event_data = json.loads(msg.data) + event_data['timestamp'] = time.time() + self.event_log.append(event_data) + except json.JSONDecodeError: + self.event_log.append({'message': msg.data, 'timestamp': time.time()}) + + def sensor_health_callback(self, msg): + try: + health = json.loads(msg.data) + self.sensor_health.update(health) + except json.JSONDecodeError: + pass + + def map_callback(self, msg): + self.map_data = { + 'width': msg.info.width, + 'height': msg.info.height, + 'resolution': msg.info.resolution, + 'origin_x': msg.info.origin.position.x, + 'origin_y': msg.info.origin.position.y, + } + + def broadcast_update(self): + """Broadcast dashboard state to all connected clients.""" + if socketio_instance is None: + return + + data = { + 'battery_percent': float(self.battery_percent), + 'battery_voltage': float(self.battery_voltage), + 'robot_state': self.robot_state, + 'motor_speeds': self.motor_speeds, + 'wifi_signal': self.wifi_signal, + 'sensor_health': self.sensor_health, + 'event_log': list(self.event_log), + 'map_data': self.map_data, + 'timestamp': time.time(), + } + + try: + socketio_instance.emit('dashboard_update', data, broadcast=True) + except Exception as e: + self.get_logger().warn(f"Failed to broadcast: {e}") + + +def create_app(dashboard_node): + """Create Flask app with dashboard routes.""" + app = Flask(__name__, template_folder='templates', static_folder='static') + app.config['SECRET_KEY'] = 'saltybot-dashboard' + + socketio = SocketIO(app, cors_allowed_origins="*") + global socketio_instance + socketio_instance = socketio + + @app.route('/') + def index(): + return render_template('dashboard.html') + + @app.route('/api/status') + def api_status(): + return jsonify({ + 'battery_percent': dashboard_node.battery_percent, + 'battery_voltage': dashboard_node.battery_voltage, + 'robot_state': dashboard_node.robot_state, + 'motor_speeds': dashboard_node.motor_speeds, + 'wifi_signal': dashboard_node.wifi_signal, + 'sensor_health': dashboard_node.sensor_health, + 'event_log': list(dashboard_node.event_log), + 'map_data': dashboard_node.map_data, + }) + + @socketio.on('connect') + def handle_connect(): + emit('response', {'data': 'Connected to SaltyBot dashboard'}) + + @socketio.on('disconnect') + def handle_disconnect(): + pass + + return app, socketio + + +def main(args=None): + rclpy.init(args=args) + dashboard_node = DashboardNode() + + app, socketio = create_app(dashboard_node) + + # Run Flask in a separate thread + def run_flask(): + socketio.run(app, host='0.0.0.0', port=8080, debug=False, allow_unsafe_werkzeug=True) + + flask_thread = Thread(target=run_flask, daemon=True) + flask_thread.start() + + # Run ROS2 spin + try: + rclpy.spin(dashboard_node) + except KeyboardInterrupt: + pass + finally: + dashboard_node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/jetson/ros2_ws/src/saltybot_dashboard/setup.cfg b/jetson/ros2_ws/src/saltybot_dashboard/setup.cfg new file mode 100644 index 0000000..bb709be --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/saltybot_dashboard +[install] +install_lib=$base/lib/python3/dist-packages diff --git a/jetson/ros2_ws/src/saltybot_dashboard/setup.py b/jetson/ros2_ws/src/saltybot_dashboard/setup.py new file mode 100644 index 0000000..557e661 --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/setup.py @@ -0,0 +1,32 @@ +from setuptools import setup +import os +from glob import glob + +package_name = 'saltybot_dashboard' + +setup( + name=package_name, + version='0.1.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name, 'launch'), glob('launch/*.py')), + (os.path.join('share', package_name, 'config'), glob('config/*.yaml')), + (os.path.join('share', package_name, 'static/css'), glob('static/css/*')), + (os.path.join('share', package_name, 'static/js'), glob('static/js/*')), + (os.path.join('share', package_name, 'templates'), glob('templates/*')), + ], + install_requires=['setuptools', 'flask', 'python-socketio', 'python-socketio-client'], + zip_safe=True, + maintainer='seb', + maintainer_email='seb@vayrette.com', + description='Remote monitoring dashboard for SaltyBot with WebSocket live updates', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'dashboard_node = saltybot_dashboard.dashboard_node:main', + ], + }, +) diff --git a/jetson/ros2_ws/src/saltybot_dashboard/static/css/dashboard.css b/jetson/ros2_ws/src/saltybot_dashboard/static/css/dashboard.css new file mode 100644 index 0000000..ecb286e --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/static/css/dashboard.css @@ -0,0 +1,334 @@ +* { + margin: 0; + padding: 0; + box-sizing: border-box; +} + +:root { + --primary: #2196F3; + --success: #4CAF50; + --warning: #FF9800; + --danger: #f44336; + --dark: #1a1a1a; + --light: #f5f5f5; + --border: #ddd; +} + +html, body { + font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, Oxygen, Ubuntu, Cantarell, sans-serif; + background: #0a0e27; + color: #fff; + height: 100%; +} + +.container { + max-width: 1400px; + margin: 0 auto; + padding: 20px; + display: flex; + flex-direction: column; + min-height: 100vh; +} + +header { + display: flex; + justify-content: space-between; + align-items: center; + margin-bottom: 30px; + padding-bottom: 20px; + border-bottom: 2px solid #333; +} + +header h1 { + font-size: 28px; + font-weight: 600; +} + +.connection-status { + display: flex; + align-items: center; + gap: 8px; + font-size: 14px; +} + +.status-dot { + width: 12px; + height: 12px; + border-radius: 50%; + background: #999; + animation: pulse 2s infinite; +} + +.status-dot.connected { + background: #4CAF50; +} + +@keyframes pulse { + 0%, 100% { opacity: 1; } + 50% { opacity: 0.5; } +} + +main { + flex: 1; + display: flex; + flex-direction: column; + gap: 20px; +} + +.grid-2 { + display: grid; + grid-template-columns: 1fr 1fr; + gap: 20px; +} + +.grid-full { + display: grid; + grid-template-columns: 1fr; +} + +.card { + background: #1a1a2e; + border: 1px solid #333; + border-radius: 8px; + padding: 20px; + box-shadow: 0 2px 8px rgba(0,0,0,0.3); +} + +.card h2 { + font-size: 18px; + margin-bottom: 15px; + color: #fff; +} + +/* Battery Card */ +.battery-display { + display: flex; + gap: 15px; + align-items: center; +} + +.battery-bar { + flex: 1; + height: 40px; + background: #333; + border-radius: 20px; + overflow: hidden; + border: 2px solid #555; +} + +.battery-fill { + height: 100%; + background: linear-gradient(90deg, #4CAF50, #8BC34A); + width: 100%; + transition: width 0.3s ease; +} + +.battery-text { + display: flex; + flex-direction: column; + align-items: center; + min-width: 80px; +} + +.battery-text span:first-child { + font-size: 24px; + font-weight: bold; +} + +.subtitle { + font-size: 12px; + color: #999; +} + +/* State Card */ +.state-display { + display: flex; + flex-direction: column; + gap: 12px; +} + +.state-badge { + display: inline-block; + padding: 8px 16px; + background: #2196F3; + border-radius: 20px; + font-weight: bold; + text-align: center; +} + +.sensor-health { + display: flex; + justify-content: space-around; + gap: 10px; +} + +.health-item { + display: flex; + align-items: center; + gap: 6px; + font-size: 16px; +} + +.health-ok { + color: #4CAF50; +} + +.health-error { + color: #f44336; +} + +/* Motors Card */ +.motors-display { + display: flex; + flex-direction: column; + gap: 15px; +} + +.motor-item { + display: flex; + align-items: center; + gap: 10px; +} + +.motor-item label { + min-width: 50px; + font-weight: 600; +} + +.motor-meter { + flex: 1; + height: 30px; + background: #333; + border-radius: 15px; + overflow: hidden; + border: 1px solid #555; +} + +.motor-bar { + height: 100%; + background: linear-gradient(90deg, #FF9800, #F44336); + width: 0%; + transition: width 0.2s ease; +} + +.motor-item span:last-child { + min-width: 70px; + text-align: right; + font-size: 12px; + color: #999; +} + +/* WiFi Card */ +.wifi-display { + display: flex; + align-items: center; + gap: 20px; + padding: 15px; +} + +.wifi-icon { + font-size: 40px; +} + +.wifi-text { + display: flex; + flex-direction: column; +} + +.wifi-text span:first-child { + font-size: 20px; + font-weight: bold; +} + +/* Map Card */ +.map-display { + width: 100%; + height: 300px; + background: #0a0e27; + border: 1px solid #333; + border-radius: 4px; +} + +.map-info { + margin-top: 10px; + font-size: 12px; + color: #999; +} + +/* Events Card */ +.event-list { + max-height: 300px; + overflow-y: auto; +} + +.event-item { + padding: 10px; + margin-bottom: 8px; + background: #0a0e27; + border-left: 3px solid #2196F3; + border-radius: 4px; + font-size: 13px; + line-height: 1.4; +} + +.event-time { + color: #999; + font-size: 11px; +} + +.placeholder { + color: #666; + text-align: center; + padding: 20px; +} + +footer { + text-align: center; + padding-top: 20px; + border-top: 1px solid #333; + color: #999; + font-size: 12px; +} + +/* Mobile Responsive */ +@media (max-width: 768px) { + .grid-2 { + grid-template-columns: 1fr; + } + + header { + flex-direction: column; + align-items: flex-start; + gap: 10px; + } + + .map-display { + height: 250px; + } + + .container { + padding: 10px; + } + + .card { + padding: 15px; + } +} + +/* Scrollbar styling */ +::-webkit-scrollbar { + width: 8px; +} + +::-webkit-scrollbar-track { + background: #1a1a2e; +} + +::-webkit-scrollbar-thumb { + background: #444; + border-radius: 4px; +} + +::-webkit-scrollbar-thumb:hover { + background: #666; +} diff --git a/jetson/ros2_ws/src/saltybot_dashboard/templates/dashboard.html b/jetson/ros2_ws/src/saltybot_dashboard/templates/dashboard.html new file mode 100644 index 0000000..83afacb --- /dev/null +++ b/jetson/ros2_ws/src/saltybot_dashboard/templates/dashboard.html @@ -0,0 +1,112 @@ + + + + + + SaltyBot Dashboard + + + + +
+
+

🤖 SaltyBot Monitor

+
+ + Connecting... +
+
+ +
+ +
+
+

⚡ Battery

+
+
+
+
+
+ 100% + 12.4V +
+
+
+ +
+

🎯 State

+
+ IDLE +
+ 📷 + 🔍 + 🎤 + 📡 +
+
+
+
+ + +
+
+

⚙️ Motors

+
+
+ +
+
+
+ 0 RPM +
+
+ +
+
+
+ 0 RPM +
+
+
+ +
+

📶 WiFi

+
+
📡
+
+ -50 dBm + Signal Strength +
+
+
+
+ + +
+
+

🗺️ Map

+ +
+ -- | -- +
+
+
+ +
+
+

📋 Event Log (Last 20)

+
+

Waiting for events...

+
+
+
+
+ +
+ Last update: -- +
+
+ + + +