diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile
deleted file mode 100644
index f1c9a43..0000000
--- a/.devcontainer/Dockerfile
+++ /dev/null
@@ -1,56 +0,0 @@
-ARG BASE_IMAGE=lcas.lincoln.ac.uk/lcas/ros-docker-images:jammy-cuda12.2-humble-2
-
-FROM ${BASE_IMAGE} AS base
-
-USER root
-
-ENV DEBIAN_FRONTEND=noninteractive
-
-RUN apt-get update \
- && apt-get install -qq -y --no-install-recommends \
- git \
- python3-pip \
- python3-rosdep
-
-# get the source tree and analyse it for its package.xml only
-FROM base AS sourcefilter
-COPY ./src /tmp/src
-# remove everything that isn't package.xml
-RUN find /tmp/src -type f \! -name "package.xml" -print | xargs rm -rf
-
-# install all dependencies listed in the package.xml
-FROM base AS depbuilder
-# copy the reduced source tree (only package.xml) from previous stage
-COPY --from=sourcefilter /tmp/src /tmp/src
-RUN rosdep update --rosdistro ${ROS_DISTRO} && apt-get update \
- && rosdep install --from-paths /tmp/src --ignore-src -r -y && rm -rf /tmp/src
-
-FROM depbuilder AS devcontainer
-# add user ros with sudo rights if it doesn't exist
-ARG GIT_REPO_VERSION="unknown"
-ARG GIT_REPO_VERSION_DATE="unknown"
-
-# export docker iamge build informaton to environment
-ENV GIT_REPO_VERSION=${GIT_REPO_VERSION}
-ENV GIT_REPO_VERSION_DATE=${GIT_REPO_VERSION_DATE}
-
-USER ros
-
-FROM depbuilder AS final
-# add user ros with sudo rights if it doesn't exist
-ARG GIT_REPO_VERSION="unknown"
-ARG GIT_REPO_VERSION_DATE="unknown"
-
-# export docker iamge build informaton to environment
-ENV GIT_REPO_VERSION=${GIT_REPO_VERSION}
-ENV GIT_REPO_VERSION_DATE=${GIT_REPO_VERSION_DATE}
-
-USER ros
-
-RUN mkdir -p ${HOME}/workspace/src
-COPY . ${HOME}/workspace/src/repository
-WORKDIR ${HOME}/workspace/
-RUN rosdep update --rosdistro ${ROS_DISTRO} && sudo apt-get update \
- && rosdep install --from-paths ./src --ignore-src -r -y \
- && bash -c "source /opt/ros/${ROS_DISTRO}/setup.sh; colcon build"
-
diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json
deleted file mode 100644
index 9b4b4dd..0000000
--- a/.devcontainer/devcontainer.json
+++ /dev/null
@@ -1,46 +0,0 @@
-// For format details, see https://aka.ms/devcontainer.json. For config options, see the
-// README at: https://github.com/devcontainers/templates/tree/main/src/ubuntu
-{
- "name": "L-CAS Humble CUDA-OpenGL Devcontainer",
- "build": {
- "dockerfile": "./Dockerfile",
- "args": {
- "BASE_IMAGE": "lcas.lincoln.ac.uk/lcas/ros-docker-images:jammy-cuda12.2-humble-2",
- "GIT_REPO_VERSION": "devcontainer",
- "GIT_REPO_VERSION_DATE": "devcontainer"
- },
- "context": "..",
- "target": "devcontainer"
- },
-
- "forwardPorts": [5801],
- "portsAttributes": {
- "5801": {
- "label": "desktop",
- "onAutoForward": "openBrowser"
- }
- },
-
- "postStartCommand": "/opt/entrypoint.sh /bin/true; .devcontainer/post-create.sh",
-
- "remoteUser": "ros",
- "updateRemoteUserUID": true, // ensure internal user has the same UID as the host user and update file permissions
- "customizations": {
- "vscode": {
- "extensions": [
- "ms-python.python",
- "GitHub.vscode-pull-request-github",
- "ms-vscode.cpptools",
- "JaehyunShim.vscode-ros2",
- "nonanonno.vscode-ros2",
- "deitry.colcon-helper",
- "github.vscode-github-actions"
- ]
- }
- },
- "hostRequirements": {
- "gpu": "optional",
- "cpus": 2,
- "memory": "8gb"
- }
-}
diff --git a/.devcontainer/post-create.sh b/.devcontainer/post-create.sh
deleted file mode 100755
index 9d9d6ff..0000000
--- a/.devcontainer/post-create.sh
+++ /dev/null
@@ -1,38 +0,0 @@
-#!/bin/bash
-
-set -xe
-
-
-function add_config_if_not_exist {
- if ! grep -F -q "$1" $HOME/.bashrc; then
- echo "$1" >> $HOME/.bashrc
- fi
-}
-
-function add_git_config_if_not_exist {
- if ! git config --global --get "$1" > /dev/null; then
- git config --global "$1" "$2"
- fi
-}
-
-add_config_if_not_exist "source /opt/ros/humble/setup.bash"
-
-source /opt/ros/humble/setup.bash
-
-colcon build --symlink-install --continue-on-error || true
-
-LOCAL_SETUP_FILE=`pwd`/install/setup.bash
-add_config_if_not_exist "if [ -r $LOCAL_SETUP_FILE ]; then source $LOCAL_SETUP_FILE; fi"
-
-
-add_git_config_if_not_exist "core.autocrlf" "input"
-add_git_config_if_not_exist "core.safecrlf" "warn"
-add_git_config_if_not_exist "pull.rebase" "false"
-add_git_config_if_not_exist "user.name" "Anonymous L-CAS DevContainer User"
-add_git_config_if_not_exist "user.email" "noreply@lcas.lincoln.ac.uk"
-add_git_config_if_not_exist "init.defaultBranch" "main"
-
-
-sleep 10
-# hack to set L-CAS background
-DISPLAY=:1 xfconf-query -c xfce4-desktop -p $(xfconf-query -c xfce4-desktop -l | grep "workspace0/last-image") -s /usr/share/backgrounds/xfce/lcas.jpg || true
diff --git a/.dockerignore b/.dockerignore
deleted file mode 100644
index ec6adb6..0000000
--- a/.dockerignore
+++ /dev/null
@@ -1,16 +0,0 @@
-./LICENSE
-./README.md
-devel/
-log/
-build/
-bin/
-lib/
-install/
-*~
-
-.git
-.gitignore
-.dockerignore
-.gitmodules
-
-.keep
diff --git a/.github/workflows/build-docker.yml b/.github/workflows/build-docker.yml
deleted file mode 100644
index 4e26531..0000000
--- a/.github/workflows/build-docker.yml
+++ /dev/null
@@ -1,84 +0,0 @@
-name: Docker Image CI
-
-on:
- push:
- branches: ["main"]
- # ensure that version tags also trigger a build, naming convention is `vX.Y.Z`
- # make sure the naming convention is followed in tags.
- tags:
- - "v*"
- pull_request:
- branches: ["main"]
- # permit manual trigger as well
- workflow_dispatch:
-
-jobs:
- build:
- # this only works on LCAS organisation and should be skipped otherwise
- if: github.repository_owner == 'LCAS'
- runs-on: ubuntu-latest
-
- steps:
- - name: Git Checkout
- uses: actions/checkout@v5
- with:
- fetch-depth: 1
-
- # log in to docker registry with correct permission
- # only works within LCAS organisation and NOT on forks
- - name: Docker Login LCAS
- uses: docker/login-action@v2
- with:
- registry: lcas.lincoln.ac.uk
- username: ${{ secrets.LCAS_REGISTRY_PUSHER }}
- password: ${{ secrets.LCAS_REGISTRY_TOKEN }}
-
- # create a docker image name from the github repository name, ensuring lower case and no disallowed characters
- - name: create docker image name from github name
- id: docker-image-name
- run: |
- repo_name=$(echo "${{ github.repository }}" | tr '[:upper:]' '[:lower:]' | tr '. ' '-')
- echo "image_name=$repo_name" >> $GITHUB_OUTPUT
-
- # set the relevant docker tags and labels
- - name: Docker meta
- id: meta
- uses: docker/metadata-action@v5
- with:
- # list of Docker images to use as base name for tags
- labels: |
- uk.ac.lincoln.lcas.repository=${{ github.repository }}
- uk.ac.lincoln.lcas.commit_sha=${{ github.sha }}
- uk.ac.lincoln.lcas.build_date=${{ github.event.head_commit.timestamp }}
- uk.ac.lincoln.lcas.version=${{ github.ref_name }}
- uk.ac.lincoln.lcas.builder=${{ github.actor }}
- images: |
- lcas.lincoln.ac.uk/${{ steps.docker-image-name.outputs.image_name }}
- flavor: |
- latest=auto
- tags: |
- type=semver,pattern={{version}}
- type=semver,pattern={{major}}.{{minor}}
- type=semver,pattern={{major}}
- type=raw,value=latest,enable={{is_default_branch}}
- type=ref,event=branch
-
- - name: setup buildx
- uses: docker/setup-buildx-action@v2
-
- - name: Build and Push
- uses: docker/build-push-action@v6
- with:
- context: .
- file: ./.devcontainer/Dockerfile
- platforms: linux/amd64 # add other platforms if needed
- cache-from: type=gha
- cache-to: type=gha,mode=max
- push: ${{ github.event_name != 'pull_request' }}
- tags: ${{ steps.meta.outputs.tags }}
- labels: ${{ steps.meta.outputs.labels }}
- target: final
- build-args: |
- BASE_IMAGE=lcas.lincoln.ac.uk/lcas/ros-docker-images:jammy-cuda12.2-humble-2
- GIT_REPO_VERSION=${{ github.ref_name }}
- GIT_REPO_VERSION_DATE=${{ github.event.head_commit.timestamp }}
diff --git a/.github/workflows/dev-container.yml b/.github/workflows/dev-container.yml
deleted file mode 100644
index 3d513cf..0000000
--- a/.github/workflows/dev-container.yml
+++ /dev/null
@@ -1,46 +0,0 @@
-name: 'devcontainer CI'
-on:
- workflow_dispatch:
- pull_request:
- branches:
- - main
- push:
- branches:
- - main
-
-jobs:
- build_devcontainer:
- runs-on: ubuntu-latest
- steps:
- - name: Free Disk Space (Ubuntu)
- uses: jlumbroso/free-disk-space@54081f138730dfa15788a46383842cd2f914a1be
- with:
- # this might remove tools that are actually needed,
- # if set to "true" but frees about 6 GB
- tool-cache: false
-
- # all of these default to true, but feel free to set to
- # "false" if necessary for your workflow
- android: true
- dotnet: true
- haskell: true
- large-packages: true
- docker-images: true
- swap-storage: true
- - name: Checkout from github
- uses: actions/checkout@v3
- - name: extract the github reference
- run: echo "BRANCH=${GITHUB_REF##*/}" >> $GITHUB_ENV
- - name: "image name from repo name"
- id: docker_image_name
- run: echo "docker_image=${{ github.repository }}" | tr '[:upper:]' '[:lower:]' |sed 's/[^0-9,a-z,A-Z,=,_,\/]/-/g' >>${GITHUB_OUTPUT}
- - name: setup buildx
- uses: docker/setup-buildx-action@v2
- - name: Build and run dev container task
- uses: devcontainers/ci@v0.3
- with:
- imageName: devcontainer/${{ steps.docker_image_name.outputs.docker_image }}
- configFile: ./.devcontainer/devcontainer.json
- push: never
- cacheFrom: type=gha
- cacheTo: type=gha,mode=max
diff --git a/.github/workflows/pytest.yml b/.github/workflows/pytest.yml
deleted file mode 100644
index 3571bf0..0000000
--- a/.github/workflows/pytest.yml
+++ /dev/null
@@ -1,35 +0,0 @@
-name: Python Tests
-
-on:
- push:
- branches: [ "main" ]
- pull_request:
- branches: [ "main" ]
-
-jobs:
- test:
- runs-on: ubuntu-latest
- permissions:
- contents: read
- strategy:
- matrix:
- python-version: ["3.10"]
-
- steps:
- - uses: actions/checkout@v3
-
- - name: Set up Python ${{ matrix.python-version }}
- uses: actions/setup-python@v4
- with:
- python-version: ${{ matrix.python-version }}
-
- - name: Install dependencies
- run: |
- python -m pip install --upgrade pip
- pip install pytest
- pip install -r requirements.txt
-
- - name: Run pytest
- run: |
- cd src/ros2_svdd_monitor
- pytest test/ -v
diff --git a/.github/workflows/ros-ci.yml b/.github/workflows/ros-ci.yml
deleted file mode 100644
index ca82656..0000000
--- a/.github/workflows/ros-ci.yml
+++ /dev/null
@@ -1,70 +0,0 @@
-name: ros CI
-
-on:
- push:
- # you may want to configure the branches that this should be run on here.
- branches: [ "main" ]
- pull_request:
- branches: [ "main" ]
-
-jobs:
- test_docker: # On Linux, iterates on all ROS 1 and ROS 2 distributions.
- runs-on: ubuntu-latest
- strategy:
- matrix:
- ros_distribution:
- # - noetic
- - humble
- # - iron
-
- # Define the Docker image(s) associated with each ROS distribution.
- # The include syntax allows additional variables to be defined, like
- # docker_image in this case. See documentation:
- # https://help.github.com/en/actions/reference/workflow-syntax-for-github-actions#example-including-configurations-in-a-matrix-build
- #
- # Platforms are defined in REP 3 and REP 2000:
- # https://ros.org/reps/rep-0003.html
- # https://ros.org/reps/rep-2000.html
- include:
- # Noetic Ninjemys (May 2020 - May 2025)
- # - docker_image: ubuntu:focal
- # ros_distribution: noetic
- # ros_version: 1
-
- # Humble Hawksbill (May 2022 - May 2027)
- - docker_image: ubuntu:jammy
- ros_distribution: humble
- ros_version: 2
-
- # Iron Irwini (May 2023 - November 2024)
- # - docker_image: ubuntu:jammy
- # ros_distribution: iron
- # ros_version: 2
-
- # # Rolling Ridley (No End-Of-Life)
- # - docker_image: ubuntu:jammy
- # ros_distribution: rolling
- # ros_version: 2
-
- container:
- image: ${{ matrix.docker_image }}
- steps:
- - uses: actions/checkout@v3
- - name: setup ROS environment
- uses: LCAS/setup-ros@master
- with:
- required-ros-distributions: ${{ matrix.ros_distribution }}
- - name: build and test ROS 1
- if: ${{ matrix.ros_version == 1 }}
- uses: ros-tooling/action-ros-ci@v0.3
- with:
- import-token: ${{ github.token }}
- target-ros1-distro: ${{ matrix.ros_distribution }}
- skip-tests: true
- - name: build and test ROS 2
- if: ${{ matrix.ros_version == 2 }}
- uses: ros-tooling/action-ros-ci@v0.3
- with:
- import-token: ${{ github.token }}
- target-ros2-distro: ${{ matrix.ros_distribution }}
- skip-tests: true
diff --git a/.gitignore b/.gitignore
index 9a0c931..a1cdac1 100644
--- a/.gitignore
+++ b/.gitignore
@@ -66,11 +66,11 @@ dist/
.pytest_cache/
# Trained models and data
-*.pkl
-*.csv
+# *.pkl
+# *.csv
*.bag
-models/
+# models/
# IDE
.vscode/
-.idea/
+.idea/
\ No newline at end of file
diff --git a/README.md b/README.md
index 875d2ef..ab5d10e 100644
--- a/README.md
+++ b/README.md
@@ -1,275 +1,104 @@
-# ros2_svdd_monitor
+# SVDD Anomaly Detection Methods
-[](https://github.com/LCAS/ros2_svdd_monitor/actions/workflows/pytest.yml)
-[](https://github.com/LCAS/ros2_svdd_monitor/actions/workflows/ros-ci.yml)
+This repository contains Python implementations of three anomaly detection methods using SVDD (Support Vector Data Description) approaches:
-SVDD-style anomaly detection for ROS 2 using proprioceptive sensors (IMU and cmd_vel).
+1. **ae_autoencoder**: Autoencoder-based anomaly detection
+2. **ms_svdd**: Multi-Scale SVDD for anomaly detection
+3. **svm_svdd**: SVM-based SVDD for anomaly detection
-This package implements Support Vector Data Description (SVDD) using OneClassSVM for real-time anomaly detection on robotic systems. It monitors the relationship between commanded velocities (`/cmd_vel`) and actual IMU measurements (`/imu`) to detect anomalous behavior that might indicate hardware failures, unexpected terrain, or other system issues.
+## Repository Structure
-## Features
-
-- **Proprioceptive-only monitoring**: Uses only `/cmd_vel` and `/imu` topics (no external sensors required)
-- **Feature engineering**: Extracts sliding-window features that capture the expected relationship between commanded motion and IMU response
-- **SVDD anomaly detection**: Uses OneClassSVM as a proxy for SVDD to learn normal operation patterns
-- **Real-time monitoring**: ROS 2 node that publishes anomaly detection results
-- **Configurable**: Hyperparameters (window size, nu, gamma) configurable via YAML
-- **Offline training**: Train models on recorded data before deployment
-
-## Installation
-
-### Prerequisites
-
-- ROS 2 Humble
-- Python 3.10+
-
-### Build from Source
-
-1. Clone this repository into your ROS 2 workspace:
-
-```bash
-cd ~/ros2_ws/src
-git clone https://github.com/LCAS/ros2_svdd_monitor.git
-```
-
-2. Install Python dependencies:
-
-```bash
-pip install -r ros2_svdd_monitor/requirements.txt
-```
-
-3. Build the package:
-
-```bash
-cd ~/ros2_ws
-colcon build --packages-select ros2_svdd_monitor
-source install/setup.bash
```
-
-## Quick Start
-
-### 1. Collect Training Data
-
-First, record normal operation data. You can either:
-
-**Option A: Use the built-in CSV recorder (recommended)**
-
-```bash
-# Start the CSV recorder
-ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv
-
-# In another terminal, operate your robot normally
-# (or play a rosbag of normal operation)
-ros2 bag play normal_operation.bag
-```
-
-**Option B: Record a rosbag and export to CSV later**
-
-```bash
-# Record a rosbag with /cmd_vel and /imu topics
-ros2 bag record /cmd_vel /imu -o normal_operation
-
-# Then use the CSV converter
-ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv
-ros2 bag play normal_operation
-```
-
-The CSV file should have the following columns:
-```
-timestamp,linear_x,linear_y,linear_z,angular_x,angular_y,angular_z,accel_x,accel_y,accel_z,gyro_x,gyro_y,gyro_z
-```
-
-### 2. Train the SVDD Model
-
-Train the anomaly detection model on your collected data:
-
-```bash
-ros2 run ros2_svdd_monitor train --csv training_data.csv --output-dir models/
-```
-
-This will:
-- Load the training data from CSV
-- Extract features using sliding windows
-- Train a OneClassSVM model
-- Save the trained model and scaler to `models/svdd_model.pkl` and `models/scaler.pkl`
-
-### 3. Run the Monitor
-
-Start the real-time anomaly monitor:
-
-```bash
-ros2 run ros2_svdd_monitor monitor
+.
+├── ae_autoencoder/ # Autoencoder-based anomaly detection
+│ ├── ae_autoencoder.py # Autoencoder model implementation
+│ ├── train_autoencoder.py # Training script
+│ └── eval_autoencoder.py # Evaluation script
+│
+├── ms_svdd/ # Multi-Scale SVDD
+│ ├── ms_svdd_model.py # MS-SVDD model implementation
+│ ├── train_ms_svdd.py # Training script
+│ ├── msvdd_config.yaml # Configuration file
+│ ├── msvdd_experiment.md # Experiment documentation
+│ ├── msvdd_model.pt # Trained model file
+│ └── msvdd_model_cmd_vel_imu.pt # Alternative trained model
+│
+├── svm_svdd/ # SVM-based SVDD
+│ ├── svm_svdd_model.py # SVM-SVDD model implementation
+│ ├── train_svm_svdd.py # Training script
+│ └── eval_svm_svdd.py # Evaluation script
+│
+├── examples/ # Example scripts
+│ └── generate_sample_data.py # Generate sample data for testing
+│
+├── features.py # Feature extraction utilities
+├── svdd_model.py # Base SVDD model
+├── train.py # General training utilities
+├── eval_ms_svdd.py # MS-SVDD evaluation
+├── features.npz # Extracted features dataset
+├── features_cmd_vel_imu.npz # Alternative features dataset
+└── requirements.txt # Python dependencies
```
-The monitor will:
-- Subscribe to `/cmd_vel` and `/imu` topics
-- Maintain sliding windows of recent data
-- Extract features and run anomaly detection
-- Publish results to `/svdd/anomaly` (Bool) and `/svdd/anomaly_score` (Float32)
-
-### 4. Visualize Anomalies
+## Installation
-Monitor the anomaly detection in real-time:
+Install the required Python dependencies:
```bash
-# Watch for anomalies
-ros2 topic echo /svdd/anomaly
-
-# View anomaly scores
-ros2 topic echo /svdd/anomaly_score
-
-# Use rqt_plot for visualization
-rqt_plot /svdd/anomaly_score
-```
-
-## Configuration
-
-The SVDD monitor is configured via `config/config.yaml`:
-
-```yaml
-# Sliding window parameters
-window_size: 10 # Number of recent samples for feature extraction
-
-# OneClassSVM hyperparameters
-nu: 0.1 # Upper bound on fraction of outliers (0 < nu <= 1)
-gamma: 'scale' # RBF kernel coefficient
-
-# Model paths
-model_path: 'svdd_model.pkl'
-scaler_path: 'scaler.pkl'
-
-# Anomaly detection threshold
-anomaly_threshold: 0.0 # Decision function threshold
+pip install -r requirements.txt
```
-### Hyperparameter Tuning
+## Methods Overview
-- **window_size**: Larger windows capture more temporal context but increase latency. Typical values: 5-20.
-- **nu**: Upper bound on training errors. Lower values make the model more strict. Typical values: 0.05-0.2.
-- **gamma**: Controls the RBF kernel width. Use 'scale' (default) or 'auto' for automatic selection, or specify a float value.
-- **anomaly_threshold**: Adjust this based on your false positive/negative tolerance. Default is 0.0.
+### 1. Autoencoder (ae_autoencoder)
-## How It Works
+Autoencoder-based anomaly detection that learns to reconstruct normal patterns and flags deviations as anomalies.
-### Feature Extraction
+- **Train**: `python ae_autoencoder/train_autoencoder.py`
+- **Evaluate**: `python ae_autoencoder/eval_autoencoder.py`
-The monitor extracts 20 features from sliding windows of `/cmd_vel` and `/imu` data:
+### 2. Multi-Scale SVDD (ms_svdd)
-**Command Velocity Features (8):**
-- Mean, std, min, max of linear.x (forward velocity)
-- Mean, std, min, max of angular.z (yaw rate)
+Multi-scale Support Vector Data Description for anomaly detection with multiple resolution levels.
-**IMU Features (8):**
-- Mean, std, min, max of accel.x (forward acceleration)
-- Mean, std, min, max of gyro.z (yaw angular velocity)
+- **Train**: `python ms_svdd/train_ms_svdd.py`
+- **Pre-trained models**:
+ - `msvdd_model.pt`
+ - `msvdd_model_cmd_vel_imu.pt`
+- **Configuration**: See `ms_svdd/msvdd_config.yaml`
+- **Documentation**: See `ms_svdd/msvdd_experiment.md`
-**Cross-Features (4):**
-- Correlation between cmd_vel.linear.x and imu.accel.x
-- Correlation between cmd_vel.angular.z and imu.gyro.z
-- Ratio of imu.accel to cmd_vel.linear
-- Ratio of imu.gyro to cmd_vel.angular
+### 3. SVM SVDD (svm_svdd)
-These features capture the expected physical relationship between commanded motion and sensor response. Anomalies occur when this relationship breaks down (e.g., wheel slip, motor failure, unexpected obstacles).
+Classic SVM-based Support Vector Data Description using OneClassSVM.
-### SVDD Model
+- **Train**: `python svm_svdd/train_svm_svdd.py`
+- **Evaluate**: `python svm_svdd/eval_svm_svdd.py`
-The OneClassSVM is trained on features extracted from normal operation data. It learns a decision boundary that encompasses normal operation patterns. During monitoring, new feature vectors are classified as:
+## Data Files
-- **Inliers (normal)**: Decision function > threshold
-- **Outliers (anomalies)**: Decision function < threshold
+- `features.npz`: Pre-extracted features for training and evaluation
+- `features_cmd_vel_imu.npz`: Alternative feature dataset with command velocity and IMU data
-The decision function value is published as the anomaly score, allowing for tunable sensitivity.
+## Feature Extraction
-## Example Use Cases
+The `features.py` module provides utilities for extracting features from time-series data. Features include:
+- Statistical measures (mean, std, min, max)
+- Temporal features from sliding windows
+- Cross-features capturing relationships between variables
-1. **Wheel slip detection**: Commanded forward motion without corresponding IMU acceleration
-2. **Motor failure**: No angular velocity despite commanded turning
-3. **Collision detection**: Unexpected deceleration (high negative acceleration)
-4. **Terrain anomaly**: Unusual vibration patterns in IMU during motion
-5. **Sensor failure**: Loss of correlation between command and measurement
+## Examples
-## Testing
-
-Run unit tests with pytest:
+The `examples/` directory contains scripts for generating sample data:
```bash
-cd src/ros2_svdd_monitor
-pytest test/ -v
+python examples/generate_sample_data.py
```
-Tests cover:
-- Feature extraction correctness
-- Model training and prediction
-- Model save/load functionality
-- Edge cases (empty windows, missing data)
-
-## Development
-
-This package includes a devcontainer for development:
-
-1. Open the repository in VS Code
-2. Click "Reopen in Container" when prompted
-3. The container includes ROS 2 Humble and all dependencies
-
-See the template README for more details on devcontainer usage.
-
-## Topics
-
-### Subscribed Topics
-
-- `/cmd_vel` (geometry_msgs/Twist): Commanded velocity
-- `/imu` (sensor_msgs/Imu): IMU measurements
-
-### Published Topics
-
-- `/svdd/anomaly` (std_msgs/Bool): True if anomaly detected
-- `/svdd/anomaly_score` (std_msgs/Float32): Anomaly score (decision function value)
-
## License
This project is licensed under the MIT License - see the [LICENSE](LICENSE) file for details.
-## Contributing
-
-Contributions are welcome! Please feel free to submit a Pull Request.
-
-## Citation
-
-If you use this package in your research, please cite:
-
-```bibtex
-@software{ros2_svdd_monitor,
- title = {ros2_svdd_monitor: SVDD Anomaly Detection for ROS 2},
- author = {LCAS},
- year = {2025},
- url = {https://github.com/LCAS/ros2_svdd_monitor}
-}
-```
-
-## Acknowledgments
-
-This package was created from the [LCAS ROS 2 Package Template](https://github.com/LCAS/ros2_pkg_template).
-
-## Troubleshooting
-
-### Model file not found
-Ensure you've trained a model first using the `train` command. Check that the model path in `config.yaml` points to the correct location.
-
-### No anomaly detection
-- Check that both `/cmd_vel` and `/imu` topics are publishing data
-- Verify that the window has filled (requires `window_size` samples)
-- Try adjusting the `anomaly_threshold` in the config
-
-### Too many false positives
-- Increase `anomaly_threshold` (more lenient)
-- Increase `nu` during training (allows more outliers)
-- Collect more diverse training data
-
-### Too many false negatives
-- Decrease `anomaly_threshold` (more strict)
-- Decrease `nu` during training (stricter model)
-- Ensure training data only contains normal operation
-
## References
- Tax, D. M., & Duin, R. P. (2004). Support vector data description. Machine learning, 54(1), 45-66.
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ae_autoencoder/ae_autoencoder.py b/ae_autoencoder/ae_autoencoder.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ae_autoencoder/ae_autoencoder.py
rename to ae_autoencoder/ae_autoencoder.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ae_autoencoder/eval_autoencoder.py b/ae_autoencoder/eval_autoencoder.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ae_autoencoder/eval_autoencoder.py
rename to ae_autoencoder/eval_autoencoder.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ae_autoencoder/train_autoencoder.py b/ae_autoencoder/train_autoencoder.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ae_autoencoder/train_autoencoder.py
rename to ae_autoencoder/train_autoencoder.py
diff --git a/features.npz b/features.npz
new file mode 100644
index 0000000..639e724
Binary files /dev/null and b/features.npz differ
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/features.py b/features.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/features.py
rename to features.py
diff --git a/features/range_mini_2/features.npz b/features/range_mini_2/features.npz
new file mode 100644
index 0000000..639e724
Binary files /dev/null and b/features/range_mini_2/features.npz differ
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/features.npz b/features/turtlebot/features.npz
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/features.npz
rename to features/turtlebot/features.npz
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/features_cmd_vel_imu.npz b/features/turtlebot/features_cmd_vel_imu.npz
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/features_cmd_vel_imu.npz
rename to features/turtlebot/features_cmd_vel_imu.npz
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/eval_ms_svdd.py b/ms_svdd/eval_ms_svdd.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/eval_ms_svdd.py
rename to ms_svdd/eval_ms_svdd.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/ms_svdd_model.py b/ms_svdd/ms_svdd_model.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/ms_svdd_model.py
rename to ms_svdd/ms_svdd_model.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/ms_svdd_node.py b/ms_svdd/ms_svdd_node.py
similarity index 99%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/ms_svdd_node.py
rename to ms_svdd/ms_svdd_node.py
index 10344d6..2274ddb 100644
--- a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/ms_svdd_node.py
+++ b/ms_svdd/ms_svdd_node.py
@@ -105,7 +105,7 @@ def __init__(self, config_path=None):
self.score_pub = self.create_publisher(Float32, '/ms_svdd/anomaly_score', 10)
self.create_subscription(Twist, '/cmd_vel', self.cmd_vel_cb, 10)
- self.create_subscription(Imu, '/imu', self.imu_cb, 10)
+ self.create_subscription(Imu, '/imu/data_raw', self.imu_cb, 10)
self.create_subscription(Odometry, '/odom', self.odom_cb, 10)
def cmd_vel_cb(self, msg: Twist):
diff --git a/ms_svdd/msvdd_config.yaml b/ms_svdd/msvdd_config.yaml
new file mode 100644
index 0000000..3dfe14b
--- /dev/null
+++ b/ms_svdd/msvdd_config.yaml
@@ -0,0 +1,3 @@
+model_path: msvdd_model.pt
+window_size: 10
+threshold: 0.5
\ No newline at end of file
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_experiment.md b/ms_svdd/msvdd_experiment.md
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_experiment.md
rename to ms_svdd/msvdd_experiment.md
diff --git a/ms_svdd/msvdd_model.pt b/ms_svdd/msvdd_model.pt
new file mode 100644
index 0000000..9fd3c17
Binary files /dev/null and b/ms_svdd/msvdd_model.pt differ
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/train_ms_svdd.py b/ms_svdd/train_ms_svdd.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/train_ms_svdd.py
rename to ms_svdd/train_ms_svdd.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_model.pt b/ms_svdd/turtlebot/msvdd_model.pt
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_model.pt
rename to ms_svdd/turtlebot/msvdd_model.pt
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_model_cmd_vel_imu.pt b/ms_svdd/turtlebot/msvdd_model_cmd_vel_imu.pt
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_model_cmd_vel_imu.pt
rename to ms_svdd/turtlebot/msvdd_model_cmd_vel_imu.pt
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/record_features.py b/record_features.py
similarity index 95%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/record_features.py
rename to record_features.py
index a3e3562..7ce8b99 100644
--- a/src/ros2_svdd_monitor/ros2_svdd_monitor/record_features.py
+++ b/record_features.py
@@ -1,10 +1,10 @@
#!/usr/bin/env python3
-"""Record /cmd_vel and /imu for a duration and save sliding-window features.
+"""Record /cmd_vel, /odom and /imu for a duration and save sliding-window features.
Usage:
python3 record_features.py --duration 30 --rate 10 --window-size 10 --out features.npz
-The script subscribes to `/cmd_vel` and `/imu`, records messages, aligns them
+The script subscribes to `/cmd_vel`, `/odom` and `/imu`, records messages, aligns them
to a time grid at `--rate` Hz, computes sliding-window features using
`extract_window_features`, and saves array `X` into an .npz file.
"""
@@ -55,7 +55,7 @@ def __init__(self):
self.odom_times = []
self.odom_vals = []
self.sub_cmd = self.create_subscription(Twist, '/cmd_vel', self.cb_cmd, 10)
- self.sub_imu = self.create_subscription(Imu, '/imu', self.cb_imu, 10)
+ self.sub_imu = self.create_subscription(Imu, '/imu/data_raw', self.cb_imu, 10)
self.sub_odom = self.create_subscription(Odometry, '/odom', self.cb_odom, 10)
def cb_cmd(self, msg: Twist):
diff --git a/src/.keep b/src/.keep
deleted file mode 100644
index e69de29..0000000
diff --git a/src/ros2_svdd_monitor/config/config.yaml b/src/ros2_svdd_monitor/config/config.yaml
deleted file mode 100644
index eacda7e..0000000
--- a/src/ros2_svdd_monitor/config/config.yaml
+++ /dev/null
@@ -1,44 +0,0 @@
-# SVDD Monitor Configuration
-
-# ROS 2 Topic Names
-cmd_vel_topic: '/cmd_vel' # Topic for velocity commands
-imu_topic: '/imu' # Topic for IMU sensor data
-odom_topic: '/odom' # Topic for odometry (nav_msgs/Odometry)
-
-# Sliding window parameters
-window_size: 10 # Number of recent samples to use for feature extraction
-
-# OneClassSVM hyperparameters
-nu: 0.2 # Upper bound on fraction of training errors and lower bound on fraction of support vectors (increased to 20% for more tolerance)
-gamma: 'scale' # Kernel coefficient for RBF ('scale' or 'auto' or float value)
-
-# Model paths
-model_path: '~/ros2_ws/src/ros2_svdd_monitor/src/ros2_svdd_monitor/ros2_svdd_monitor/models/svm_model.pkl' # Path to save/load trained model (existing OneClassSVM)
-scaler_path: '~/ros2_ws/src/ros2_svdd_monitor/src/ros2_svdd_monitor/ros2_svdd_monitor/models/svm_scaler.pkl' # Path to save/load feature scaler
-
-# Anomaly detection threshold
-# Predictions from OneClassSVM: 1 for inliers, -1 for outliers
-# Decision function returns signed distance to separating hyperplane
-# If use_auto_threshold is true, the monitor will load the threshold saved by training
-use_auto_threshold: true
-enter_threshold_percentile: 1.0 # Percentile for anomaly entry threshold (training time)
-exit_threshold_percentile: 5.0 # Percentile for anomaly exit threshold (training time)
-threshold_path: 'threshold.yaml' # Where training writes the threshold (relative to model directory)
-anomaly_threshold: -8.0 # Fallback threshold if auto-threshold is not available
-
-# Training parameters
-test_size: 0.2 # Fraction of data to use for validation (optional)
-random_state: 42 # Random seed for reproducibility
-
-# Feature extraction parameters
-# Features include statistics (mean, std, min, max) of cmd_vel and IMU data over the window
-feature_scaling: true # Whether to scale features before training/inference
-include_odom_features: true # Whether to include odom-derived features (set false if odom not available)
-
-# Runtime smoothing and hysteresis to reduce flicker
-smoothing_alpha: 0.2 # 0..1, higher = less smoothing (EMA of score)
-hysteresis_abs_margin: 0.5 # Absolute margin added to threshold for exit
-hysteresis_ratio: 0.05 # Or ratio of |threshold|; effective margin = max(abs_margin, |thr|*ratio)
-hysteresis_abs_max: 50.0 # Cap the margin to avoid huge exit thresholds
-enter_consecutive: 2 # Require N consecutive crossings to enter anomaly
-exit_consecutive: 2 # Require N consecutive normals to exit anomaly
diff --git a/src/ros2_svdd_monitor/package.xml b/src/ros2_svdd_monitor/package.xml
deleted file mode 100644
index 7780f41..0000000
--- a/src/ros2_svdd_monitor/package.xml
+++ /dev/null
@@ -1,26 +0,0 @@
-
-
-
- ros2_svdd_monitor
- 0.1.0
- SVDD-style anomaly detection for ROS 2 using proprioceptive sensors (IMU and cmd_vel)
- LCAS
- MIT
-
- rclpy
- std_msgs
- geometry_msgs
- sensor_msgs
-
- python3-numpy
- python3-sklearn
- python3-pandas
- python3-joblib
- python3-yaml
-
- python3-pytest
-
-
- ament_python
-
-
diff --git a/src/ros2_svdd_monitor/pytest.ini b/src/ros2_svdd_monitor/pytest.ini
deleted file mode 100644
index 4e3badb..0000000
--- a/src/ros2_svdd_monitor/pytest.ini
+++ /dev/null
@@ -1,6 +0,0 @@
-[pytest]
-testpaths = test
-python_files = test_*.py
-python_classes = Test*
-python_functions = test_*
-addopts = -v --tb=short
diff --git a/src/ros2_svdd_monitor/resource/ros2_svdd_monitor b/src/ros2_svdd_monitor/resource/ros2_svdd_monitor
deleted file mode 100644
index e69de29..0000000
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/__init__.py b/src/ros2_svdd_monitor/ros2_svdd_monitor/__init__.py
deleted file mode 100644
index e69de29..0000000
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/monitor.py b/src/ros2_svdd_monitor/ros2_svdd_monitor/monitor.py
deleted file mode 100644
index d08f38e..0000000
--- a/src/ros2_svdd_monitor/ros2_svdd_monitor/monitor.py
+++ /dev/null
@@ -1,454 +0,0 @@
-#!/usr/bin/env python3
-"""
-SVDD Anomaly Monitor Node
-
-This ROS 2 node subscribes to /cmd_vel and /imu topics, maintains sliding windows,
-extracts features, and publishes anomaly detection results.
-
-Publishes:
- /svdd/anomaly (std_msgs/Bool): True if anomaly detected
- /svdd/anomaly_score (std_msgs/Float32): Anomaly score (decision function value)
-"""
-
-import os
-import sys
-import yaml
-from collections import deque
-import numpy as np
-
-import rclpy
-from rclpy.node import Node
-from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy, DurabilityPolicy
-from geometry_msgs.msg import Twist
-from sensor_msgs.msg import Imu
-from nav_msgs.msg import Odometry
-from std_msgs.msg import Bool, Float32
-from ament_index_python.packages import get_package_share_directory
-
-from ros2_svdd_monitor.svdd_model import SVDDModel
-import inspect
-
-def _load_local_features():
- import importlib.util
- local_features_path = os.path.join(os.path.dirname(__file__), 'features.py')
- spec = importlib.util.spec_from_file_location('local_features', local_features_path)
- local_features = importlib.util.module_from_spec(spec)
- spec.loader.exec_module(local_features)
- return local_features.extract_window_features
-
-try:
- from ros2_svdd_monitor.features import extract_window_features
- # Verify signature supports optional odom_window (3rd arg)
- try:
- sig = inspect.signature(extract_window_features)
- if len(sig.parameters) < 2:
- # unexpected signature, load local implementation
- extract_window_features = _load_local_features()
- else:
- # if it only accepts 2 params, replace with local implementation
- if len(sig.parameters) == 2:
- extract_window_features = _load_local_features()
- except Exception:
- # If signature inspection fails, prefer local implementation
- extract_window_features = _load_local_features()
-except Exception:
- # Fallback: load local features.py to avoid using an installed/stale package
- extract_window_features = _load_local_features()
-
-
-class SVDDMonitor(Node):
- """
- ROS 2 node for real-time SVDD-based anomaly detection.
- """
-
- def __init__(self, config_path=None):
- super().__init__('svdd_monitor')
-
- # Load configuration
- self.config = self.load_config(config_path)
-
- # Initialize sliding windows
- self.window_size = self.config['window_size']
- self.cmd_vel_window = deque(maxlen=self.window_size)
- self.imu_window = deque(maxlen=self.window_size)
- self.odom_window = deque(maxlen=self.window_size)
-
- # Load trained model
- self.model = SVDDModel()
- model_path = os.path.expanduser(self.config['model_path'])
- scaler_path = os.path.expanduser(self.config['scaler_path'])
-
- if not os.path.exists(model_path):
- self.get_logger().error(f"Model file not found: {model_path}")
- self.get_logger().error("Please train a model first using: ros2 run ros2_svdd_monitor train")
- sys.exit(1)
-
- self.get_logger().info(f"Loading model from {model_path}...")
- self.model.load(model_path, scaler_path)
- self.get_logger().info("Model loaded successfully!")
-
- # Anomaly threshold(s)
- self.anomaly_threshold = self.config.get('anomaly_threshold', 0.0)
- self.enter_threshold = None
- self.exit_threshold = None
-
- # Optionally load auto-threshold saved at training time
- use_auto = self.config.get('use_auto_threshold', False)
- if use_auto:
- try:
- # Determine threshold file path
- threshold_path = self.config.get('threshold_path', 'threshold.yaml')
- if not os.path.isabs(threshold_path):
- # Resolve relative to model directory if not absolute
- model_dir = os.path.dirname(model_path) if os.path.dirname(model_path) else os.getcwd()
- threshold_path = os.path.join(model_dir, threshold_path)
-
- if os.path.exists(threshold_path):
- with open(threshold_path, 'r') as f:
- tconf = yaml.safe_load(f)
- if isinstance(tconf, dict):
- if 'enter_threshold' in tconf and 'exit_threshold' in tconf:
- self.enter_threshold = float(tconf['enter_threshold'])
- self.exit_threshold = float(tconf['exit_threshold'])
- self.get_logger().info(
- f"Loaded enter/exit thresholds from {threshold_path}: enter={self.enter_threshold}, exit={self.exit_threshold}"
- )
- elif 'threshold' in tconf:
- self.anomaly_threshold = float(tconf['threshold'])
- self.get_logger().info(f"Loaded threshold from {threshold_path}: {self.anomaly_threshold}")
- else:
- self.get_logger().warn(f"Threshold file missing expected keys: {threshold_path}")
- else:
- self.get_logger().warn(f"Auto-threshold enabled but file not found: {threshold_path}")
- except Exception as e:
- self.get_logger().warn(f"Failed to load auto-threshold: {e}")
-
- # Subscribers with flexible QoS to handle different publishers
- qos_profile = QoSProfile(
- reliability=ReliabilityPolicy.BEST_EFFORT,
- history=HistoryPolicy.KEEP_LAST,
- depth=10
- )
-
- cmd_vel_topic = self.config.get('cmd_vel_topic', '/cmd_vel')
- imu_topic = self.config.get('imu_topic', '/imu')
- odom_topic = self.config.get('odom_topic', '/odom')
-
- self.cmd_vel_sub = self.create_subscription(
- Twist,
- cmd_vel_topic,
- self.cmd_vel_callback,
- qos_profile
- )
-
- self.imu_sub = self.create_subscription(
- Imu,
- imu_topic,
- self.imu_callback,
- qos_profile
- )
-
- self.odom_sub = self.create_subscription(
- Odometry,
- odom_topic,
- self.odom_callback,
- qos_profile
- )
-
- # Publishers (latched) so last message is delivered to late subscribers
- pub_qos = QoSProfile(
- reliability=ReliabilityPolicy.RELIABLE,
- history=HistoryPolicy.KEEP_LAST,
- depth=1
- )
- pub_qos.durability = DurabilityPolicy.TRANSIENT_LOCAL
- self.anomaly_pub = self.create_publisher(Bool, '/svdd/anomaly', pub_qos)
- self.score_pub = self.create_publisher(Float32, '/svdd/anomaly_score', pub_qos)
-
- # Statistics
- self.message_count = 0
- self.anomaly_count = 0
- self.warmup_samples = 50 # Skip first N samples to let windows stabilize
-
- # Smoothing and hysteresis
- self.smoothing_alpha = float(self.config.get('smoothing_alpha', 0.2))
- self.hysteresis_abs_margin = float(self.config.get('hysteresis_abs_margin', 0.5))
- self.hysteresis_ratio = float(self.config.get('hysteresis_ratio', 0.05))
- self.enter_consecutive = int(self.config.get('enter_consecutive', 2))
- self.exit_consecutive = int(self.config.get('exit_consecutive', 2))
- self.smoothed_score = None
- self.in_anomaly = False
- self.consec_anom = 0
- self.consec_norm = 0
-
- self.get_logger().info("SVDD Monitor started!")
- self.get_logger().info(f"Window size: {self.window_size}")
- if self.enter_threshold is not None and self.exit_threshold is not None:
- self.get_logger().info(f"Enter/Exit thresholds: {self.enter_threshold} / {self.exit_threshold}")
- else:
- self.get_logger().info(f"Anomaly threshold: {self.anomaly_threshold}")
- self.get_logger().info(f"Subscribing to {cmd_vel_topic} and {imu_topic}")
- self.get_logger().info(f"Subscribing to odom: {odom_topic}")
- self.get_logger().info("Publishing to /svdd/anomaly and /svdd/anomaly_score")
-
- def load_config(self, config_path=None):
- """Load configuration from YAML file."""
- # If a config_path was provided but doesn't exist, attempt sensible fallbacks
- if config_path is not None:
- config_path = os.path.expanduser(config_path)
- if not os.path.exists(config_path):
- candidates = [
- config_path,
- os.path.join(os.path.dirname(__file__), '..', config_path),
- os.path.join(os.path.dirname(__file__), '..', os.path.basename(config_path)),
- os.path.join(os.getcwd(), config_path),
- ]
- try:
- share_dir = get_package_share_directory('ros2_svdd_monitor')
- candidates.insert(0, os.path.join(share_dir, 'config', os.path.basename(config_path)))
- except Exception:
- pass
-
- found = None
- for path in candidates:
- p = os.path.normpath(path)
- if os.path.exists(p):
- found = p
- break
-
- if found is None:
- self.get_logger().error(f"Config file not found (tried): {candidates}")
- sys.exit(1)
-
- config_path = found
- else:
- # Search for config in common locations
- possible_paths = [
- 'config/config.yaml',
- '../config/config.yaml',
- os.path.join(os.path.dirname(__file__), '../config/config.yaml'),
- ]
-
- # Add the installed share directory location
- try:
- share_dir = get_package_share_directory('ros2_svdd_monitor')
- possible_paths.insert(0, os.path.join(share_dir, 'config/config.yaml'))
- except Exception:
- pass
-
- for path in possible_paths:
- if os.path.exists(path):
- config_path = path
- break
-
- if config_path is None:
- self.get_logger().error("Could not find config.yaml")
- sys.exit(1)
-
- with open(config_path, 'r') as f:
- config = yaml.safe_load(f)
-
- return config
-
- def cmd_vel_callback(self, msg):
- """Handle incoming cmd_vel messages."""
- # Store as array: [linear.x, linear.y, linear.z, angular.x, angular.y, angular.z]
- cmd_vel_data = [
- msg.linear.x,
- msg.linear.y,
- msg.linear.z,
- msg.angular.x,
- msg.angular.y,
- msg.angular.z,
- ]
- self.cmd_vel_window.append(cmd_vel_data)
-
- # Check for anomaly if we have enough data, otherwise publish defaults
- if len(self.cmd_vel_window) >= self.window_size and len(self.imu_window) >= self.window_size:
- self.check_for_anomaly()
- else:
- self.publish_defaults()
-
- def imu_callback(self, msg):
- """Handle incoming IMU messages."""
- # Store as array: [accel.x, accel.y, accel.z, gyro.x, gyro.y, gyro.z]
- imu_data = [
- msg.linear_acceleration.x,
- msg.linear_acceleration.y,
- msg.linear_acceleration.z,
- msg.angular_velocity.x,
- msg.angular_velocity.y,
- msg.angular_velocity.z,
- ]
- self.imu_window.append(imu_data)
-
- # Check for anomaly if we have enough data, otherwise publish defaults
- if len(self.cmd_vel_window) >= self.window_size and len(self.imu_window) >= self.window_size:
- self.check_for_anomaly()
- else:
- self.publish_defaults()
-
- def odom_callback(self, msg):
- """Handle incoming Odometry messages."""
- odom_data = [
- msg.twist.twist.linear.x,
- msg.twist.twist.linear.y,
- msg.twist.twist.linear.z,
- msg.twist.twist.angular.x,
- msg.twist.twist.angular.y,
- msg.twist.twist.angular.z,
- ]
- self.odom_window.append(odom_data)
-
- if len(self.cmd_vel_window) >= self.window_size and len(self.imu_window) >= self.window_size and len(self.odom_window) >= self.window_size:
- self.check_for_anomaly()
- else:
- self.publish_defaults()
-
- def publish_defaults(self):
- """Publish default messages so topics are active before detection starts."""
- anomaly_msg = Bool()
- anomaly_msg.data = False
- self.anomaly_pub.publish(anomaly_msg)
- score_msg = Float32()
- score_msg.data = 0.0
- self.score_pub.publish(score_msg)
-
- def check_for_anomaly(self):
- """
- Extract features from current windows and check for anomaly.
- """
- # Extract features from current windows
- cmd_vel_array = list(self.cmd_vel_window)
- imu_array = list(self.imu_window)
-
- features = extract_window_features(cmd_vel_array, imu_array, list(self.odom_window))
- features = features.reshape(1, -1) # Reshape for single prediction
-
- # Get anomaly score (decision function)
- raw_score = self.model.decision_function(
- features,
- scale=self.config.get('feature_scaling', True)
- )[0]
- # Smooth score with EMA to reduce flicker
- if self.smoothed_score is None:
- self.smoothed_score = float(raw_score)
- else:
- a = self.smoothing_alpha
- self.smoothed_score = float(a * raw_score + (1.0 - a) * self.smoothed_score)
- score = self.smoothed_score
-
- # Predict anomaly
- prediction = self.model.predict(
- features,
- scale=self.config.get('feature_scaling', True)
- )[0]
-
- # During warmup, publish but never flag anomaly
- if self.message_count < self.warmup_samples:
- is_anomaly = False
- self.consec_anom = 0
- self.consec_norm = 0
- else:
- # Hysteresis thresholds
- if self.enter_threshold is not None and self.exit_threshold is not None:
- enter_threshold = self.enter_threshold
- exit_threshold = self.exit_threshold
- else:
- # Symmetric margins around single threshold, clamped by abs_max
- base = self.anomaly_threshold
- margin = max(self.hysteresis_abs_margin, abs(base) * self.hysteresis_ratio)
- max_margin = float(self.config.get('hysteresis_abs_max', float('inf')))
- if np.isfinite(max_margin):
- margin = min(margin, max_margin)
- enter_threshold = base - margin
- exit_threshold = base + margin
-
- # Update consecutive counters based on score relative to thresholds
- if not self.in_anomaly:
- # Candidate to enter anomaly when below enter_threshold
- if score < enter_threshold:
- self.consec_anom += 1
- else:
- self.consec_anom = 0
- if self.consec_anom >= self.enter_consecutive:
- self.in_anomaly = True
- self.consec_anom = 0
- else:
- # Candidate to exit anomaly when above exit_threshold
- if score > exit_threshold:
- self.consec_norm += 1
- else:
- self.consec_norm = 0
- if self.consec_norm >= self.exit_consecutive:
- self.in_anomaly = False
- self.consec_norm = 0
-
- is_anomaly = self.in_anomaly
-
- # Publish results
- anomaly_msg = Bool()
- anomaly_msg.data = bool(is_anomaly)
- self.anomaly_pub.publish(anomaly_msg)
-
- score_msg = Float32()
- score_msg.data = float(score)
- self.score_pub.publish(score_msg)
-
- # Update statistics
- self.message_count += 1
- if (self.message_count >= self.warmup_samples) and is_anomaly:
- self.anomaly_count += 1
-
- # Log periodically
- if self.message_count % 100 == 0:
- anomaly_rate = self.anomaly_count / self.message_count * 100
- self.get_logger().info(
- f"Processed {self.message_count} samples, "
- f"anomalies: {self.anomaly_count} ({anomaly_rate:.2f}%)"
- )
-
- # Log anomalies with detailed diagnostics
- if is_anomaly:
- # Log raw sensor data
- cmd_vel_mean = np.mean(cmd_vel_array, axis=0)
- imu_mean = np.mean(imu_array, axis=0)
-
- self.get_logger().warn(
- f"ANOMALY DETECTED! Score: {score:.6f} (threshold: {self.anomaly_threshold}) Prediction: {prediction}"
- )
- self.get_logger().warn(
- f" cmd_vel (mean): linear=[{cmd_vel_mean[0]:.4f}, {cmd_vel_mean[1]:.4f}, {cmd_vel_mean[2]:.4f}] "
- f"angular=[{cmd_vel_mean[3]:.4f}, {cmd_vel_mean[4]:.4f}, {cmd_vel_mean[5]:.4f}]"
- )
- self.get_logger().warn(
- f" imu (mean): accel=[{imu_mean[0]:.4f}, {imu_mean[1]:.4f}, {imu_mean[2]:.4f}] "
- f"gyro=[{imu_mean[3]:.4f}, {imu_mean[4]:.4f}, {imu_mean[5]:.4f}]"
- )
- self.get_logger().warn(
- f" Features: {' '.join([f'{f:.4f}' for f in features[0][:5]])}... (showing first 5 of {len(features[0])})"
- )
-
-
-def main(args=None):
- """Main entry point for the SVDD monitor node."""
- rclpy.init(args=args)
-
- # Check for config path argument
- config_path = None
- if len(sys.argv) > 1:
- config_path = sys.argv[1]
-
- node = SVDDMonitor(config_path=config_path)
-
- try:
- rclpy.spin(node)
- except KeyboardInterrupt:
- pass
- finally:
- node.destroy_node()
- rclpy.shutdown()
-
-
-if __name__ == '__main__':
- main()
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_config.yaml b/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_config.yaml
deleted file mode 100644
index d2c5655..0000000
--- a/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_config.yaml
+++ /dev/null
@@ -1,3 +0,0 @@
-model_path: /home/jcox/ros2_ws/src/ros2_svdd_monitor/src/ros2_svdd_monitor/ros2_svdd_monitor/ms_svdd/msvdd_model.pt
-window_size: 10
-threshold: 0.5
\ No newline at end of file
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/utils/__init__.py b/src/ros2_svdd_monitor/ros2_svdd_monitor/utils/__init__.py
deleted file mode 100644
index e69de29..0000000
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/utils/rosbag_to_csv.py b/src/ros2_svdd_monitor/ros2_svdd_monitor/utils/rosbag_to_csv.py
deleted file mode 100644
index 6d3533d..0000000
--- a/src/ros2_svdd_monitor/ros2_svdd_monitor/utils/rosbag_to_csv.py
+++ /dev/null
@@ -1,168 +0,0 @@
-"""
-Rosbag to CSV Converter
-
-This utility helps export cmd_vel and imu topics from a ROS 2 bag to CSV format
-for training the SVDD model.
-
-Usage:
- ros2 run ros2_svdd_monitor rosbag_to_csv [cmd_vel_topic] [imu_topic]
-
-Examples:
- ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv
- ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv /cmd_vel /imu/data
-
-Or use this as a reference to create a custom subscriber that writes synchronized
-CSV rows during data collection.
-"""
-
-import rclpy
-from rclpy.node import Node
-from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy, DurabilityPolicy
-from geometry_msgs.msg import Twist
-from sensor_msgs.msg import Imu
-import csv
-from collections import deque
-import sys
-
-
-class BagToCSVConverter(Node):
- """
- Node to subscribe to /cmd_vel and /imu and write synchronized data to CSV.
-
- This can be run live while recording a rosbag to create training data.
- """
-
- def __init__(self, output_csv_path, cmd_vel_topic='/cmd_vel', imu_topic='/imu'):
- super().__init__('rosbag_to_csv_converter')
-
- self.output_csv_path = output_csv_path
- self.csv_file = open(output_csv_path, 'w', newline='')
- self.csv_writer = csv.writer(self.csv_file)
-
- # Write header
- self.csv_writer.writerow([
- 'timestamp',
- 'linear_x', 'linear_y', 'linear_z',
- 'angular_x', 'angular_y', 'angular_z',
- 'accel_x', 'accel_y', 'accel_z',
- 'gyro_x', 'gyro_y', 'gyro_z'
- ])
-
- # Store latest messages
- self.latest_cmd_vel = None
- self.latest_imu = None
-
- # QoS profile for better compatibility with rosbag playback
- qos_profile = QoSProfile(
- reliability=ReliabilityPolicy.BEST_EFFORT,
- durability=DurabilityPolicy.VOLATILE,
- history=HistoryPolicy.KEEP_LAST,
- depth=10
- )
-
- # Subscriptions
- self.cmd_vel_sub = self.create_subscription(
- Twist,
- cmd_vel_topic,
- self.cmd_vel_callback,
- qos_profile
- )
-
- self.imu_sub = self.create_subscription(
- Imu,
- imu_topic,
- self.imu_callback,
- qos_profile
- )
-
- self.get_logger().info(f'Recording to {output_csv_path}')
- self.get_logger().info(f'Subscribing to {cmd_vel_topic} and {imu_topic}')
-
- self.sample_count = 0
-
- def cmd_vel_callback(self, msg):
- """Store latest cmd_vel message."""
- self.latest_cmd_vel = msg
- self.try_write_row()
-
- def imu_callback(self, msg):
- """Store latest IMU message."""
- self.latest_imu = msg
- self.try_write_row()
-
- def try_write_row(self):
- """
- Write a row to CSV if we have both cmd_vel and IMU data.
- """
- if self.latest_cmd_vel is not None and self.latest_imu is not None:
- timestamp = self.get_clock().now().nanoseconds / 1e9
-
- row = [
- timestamp,
- self.latest_cmd_vel.linear.x,
- self.latest_cmd_vel.linear.y,
- self.latest_cmd_vel.linear.z,
- self.latest_cmd_vel.angular.x,
- self.latest_cmd_vel.angular.y,
- self.latest_cmd_vel.angular.z,
- self.latest_imu.linear_acceleration.x,
- self.latest_imu.linear_acceleration.y,
- self.latest_imu.linear_acceleration.z,
- self.latest_imu.angular_velocity.x,
- self.latest_imu.angular_velocity.y,
- self.latest_imu.angular_velocity.z,
- ]
-
- self.csv_writer.writerow(row)
- self.sample_count += 1
-
- if self.sample_count % 100 == 0:
- self.get_logger().info(f'Recorded {self.sample_count} samples')
-
- def __del__(self):
- """Close CSV file on cleanup."""
- if hasattr(self, 'csv_file'):
- self.csv_file.close()
- self.get_logger().info(f'Closed CSV file with {self.sample_count} samples')
-
-
-def main(args=None):
- """
- Main entry point for rosbag to CSV converter.
-
- Usage:
- ros2 run ros2_svdd_monitor rosbag_to_csv [cmd_vel_topic] [imu_topic]
-
- Examples:
- ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv
- ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv /cmd_vel /imu/data
-
- Then play your rosbag:
- ros2 bag play
-
- Or run this alongside your robot to collect training data.
- """
- if len(sys.argv) < 2:
- print("Usage: ros2 run ros2_svdd_monitor rosbag_to_csv [cmd_vel_topic] [imu_topic]")
- print("Example: ros2 run ros2_svdd_monitor rosbag_to_csv training_data.csv /cmd_vel /imu/data")
- print("Then play your rosbag: ros2 bag play ")
- return
-
- output_csv = sys.argv[1]
- cmd_vel_topic = sys.argv[2] if len(sys.argv) > 2 else '/cmd_vel'
- imu_topic = sys.argv[3] if len(sys.argv) > 3 else '/imu'
-
- rclpy.init(args=args)
- node = BagToCSVConverter(output_csv, cmd_vel_topic, imu_topic)
-
- try:
- rclpy.spin(node)
- except KeyboardInterrupt:
- pass
- finally:
- node.destroy_node()
- rclpy.shutdown()
-
-
-if __name__ == '__main__':
- main()
diff --git a/src/ros2_svdd_monitor/rosbags/dynium_system_filtered/dynium_system_filtered_0.db3 b/src/ros2_svdd_monitor/rosbags/dynium_system_filtered/dynium_system_filtered_0.db3
deleted file mode 100644
index 18eeb4f..0000000
Binary files a/src/ros2_svdd_monitor/rosbags/dynium_system_filtered/dynium_system_filtered_0.db3 and /dev/null differ
diff --git a/src/ros2_svdd_monitor/rosbags/dynium_system_filtered/metadata.yaml b/src/ros2_svdd_monitor/rosbags/dynium_system_filtered/metadata.yaml
deleted file mode 100644
index 4bf4355..0000000
--- a/src/ros2_svdd_monitor/rosbags/dynium_system_filtered/metadata.yaml
+++ /dev/null
@@ -1,32 +0,0 @@
-rosbag2_bagfile_information:
- version: 5
- storage_identifier: sqlite3
- duration:
- nanoseconds: 419249931811
- starting_time:
- nanoseconds_since_epoch: 1765300145602728297
- message_count: 28118
- topics_with_message_count:
- - topic_metadata:
- name: /gophar_vehicle_controller/cmd_vel
- type: geometry_msgs/msg/Twist
- serialization_format: cdr
- offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 2\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false"
- message_count: 23925
- - topic_metadata:
- name: /gps_base/yaw
- type: sensor_msgs/msg/Imu
- serialization_format: cdr
- offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 2\n durability: 2\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false"
- message_count: 4193
- compression_format: ""
- compression_mode: ""
- relative_file_paths:
- - dynium_system_filtered_0.db3
- files:
- - path: dynium_system_filtered_0.db3
- starting_time:
- nanoseconds_since_epoch: 1765300145602728297
- duration:
- nanoseconds: 419249931811
- message_count: 28118
\ No newline at end of file
diff --git a/src/ros2_svdd_monitor/setup.cfg b/src/ros2_svdd_monitor/setup.cfg
deleted file mode 100644
index 473ba4c..0000000
--- a/src/ros2_svdd_monitor/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[develop]
-script_dir=$base/lib/ros2_svdd_monitor
-[install]
-install_scripts=$base/lib/ros2_svdd_monitor
diff --git a/src/ros2_svdd_monitor/setup.py b/src/ros2_svdd_monitor/setup.py
deleted file mode 100644
index 7847862..0000000
--- a/src/ros2_svdd_monitor/setup.py
+++ /dev/null
@@ -1,38 +0,0 @@
-from setuptools import setup, find_packages
-import os
-from glob import glob
-
-package_name = 'ros2_svdd_monitor'
-
-setup(
- name=package_name,
- version='0.1.0',
- packages=find_packages(exclude=['test']),
- data_files=[
- ('share/ament_index/resource_index/packages',
- ['resource/' + package_name]),
- ('share/' + package_name, ['package.xml']),
- (os.path.join('share', package_name, 'config'), glob('config/*.yaml')),
- ],
- install_requires=[
- 'setuptools',
- 'scikit-learn',
- 'numpy',
- 'pandas',
- 'joblib',
- 'pyyaml',
- ],
- zip_safe=True,
- maintainer='LCAS',
- maintainer_email='lcas@lincoln.ac.uk',
- description='SVDD-style anomaly detection for ROS 2 using proprioceptive sensors',
- license='MIT',
- tests_require=['pytest'],
- entry_points={
- 'console_scripts': [
- 'train = ros2_svdd_monitor.train:main',
- 'monitor = ros2_svdd_monitor.monitor:main',
- 'rosbag_to_csv = ros2_svdd_monitor.utils.rosbag_to_csv:main',
- ],
- },
-)
diff --git a/src/ros2_svdd_monitor/test/__init__.py b/src/ros2_svdd_monitor/test/__init__.py
deleted file mode 100644
index e69de29..0000000
diff --git a/src/ros2_svdd_monitor/test/test_features.py b/src/ros2_svdd_monitor/test/test_features.py
deleted file mode 100644
index 9040da3..0000000
--- a/src/ros2_svdd_monitor/test/test_features.py
+++ /dev/null
@@ -1,148 +0,0 @@
-"""
-Unit tests for feature extraction module.
-"""
-
-import pytest
-import numpy as np
-import pandas as pd
-from ros2_svdd_monitor.features import (
- extract_window_features,
- extract_features_from_dataframe,
- get_feature_names
-)
-
-
-class TestFeatureExtraction:
- """Test suite for feature extraction functions."""
-
- def test_extract_window_features_basic(self):
- """Test basic feature extraction with simple data."""
- # Create simple cmd_vel data (linear.x=1.0, angular.z=0.5)
- cmd_vel_window = [
- [1.0, 0.0, 0.0, 0.0, 0.0, 0.5],
- [1.0, 0.0, 0.0, 0.0, 0.0, 0.5],
- [1.0, 0.0, 0.0, 0.0, 0.0, 0.5],
- ]
-
- # Create simple IMU data (accel.x=2.0, gyro.z=1.0)
- imu_window = [
- [2.0, 0.0, 0.0, 0.0, 0.0, 1.0],
- [2.0, 0.0, 0.0, 0.0, 0.0, 1.0],
- [2.0, 0.0, 0.0, 0.0, 0.0, 1.0],
- ]
-
- features = extract_window_features(cmd_vel_window, imu_window)
-
- # Check feature vector length
- assert len(features) == 20, "Should have 20 features"
-
- # Check cmd_vel linear.x statistics
- assert features[0] == 1.0, "Mean linear.x should be 1.0"
- assert features[1] == 0.0, "Std linear.x should be 0.0"
- assert features[2] == 1.0, "Min linear.x should be 1.0"
- assert features[3] == 1.0, "Max linear.x should be 1.0"
-
- # Check cmd_vel angular.z statistics
- assert features[4] == 0.5, "Mean angular.z should be 0.5"
-
- # Check IMU accel.x statistics
- assert features[8] == 2.0, "Mean accel.x should be 2.0"
-
- def test_extract_window_features_empty(self):
- """Test feature extraction with empty windows."""
- cmd_vel_window = []
- imu_window = []
-
- features = extract_window_features(cmd_vel_window, imu_window)
-
- # Should return zeros for all features
- assert len(features) == 20, "Should have 20 features"
- assert np.all(features == 0.0), "All features should be zero for empty windows"
-
- def test_extract_window_features_varying_data(self):
- """Test feature extraction with varying data."""
- # Create varying cmd_vel data
- cmd_vel_window = [
- [0.5, 0.0, 0.0, 0.0, 0.0, 0.0],
- [1.0, 0.0, 0.0, 0.0, 0.0, 0.2],
- [1.5, 0.0, 0.0, 0.0, 0.0, 0.4],
- ]
-
- # Create varying IMU data
- imu_window = [
- [1.0, 0.0, 0.0, 0.0, 0.0, 0.0],
- [2.0, 0.0, 0.0, 0.0, 0.0, 0.1],
- [3.0, 0.0, 0.0, 0.0, 0.0, 0.2],
- ]
-
- features = extract_window_features(cmd_vel_window, imu_window)
-
- # Check that statistics are computed correctly
- assert features[0] == 1.0, "Mean linear.x should be 1.0"
- assert features[1] > 0.0, "Std linear.x should be > 0"
- assert features[2] == 0.5, "Min linear.x should be 0.5"
- assert features[3] == 1.5, "Max linear.x should be 1.5"
-
- def test_extract_features_from_dataframe(self):
- """Test feature extraction from a DataFrame."""
- # Create sample DataFrame
- data = {
- 'timestamp': [1.0, 2.0, 3.0, 4.0, 5.0],
- 'linear_x': [1.0, 1.0, 1.0, 1.0, 1.0],
- 'linear_y': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'linear_z': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'angular_x': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'angular_y': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'angular_z': [0.5, 0.5, 0.5, 0.5, 0.5],
- 'accel_x': [2.0, 2.0, 2.0, 2.0, 2.0],
- 'accel_y': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'accel_z': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'gyro_x': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'gyro_y': [0.0, 0.0, 0.0, 0.0, 0.0],
- 'gyro_z': [1.0, 1.0, 1.0, 1.0, 1.0],
- }
- df = pd.DataFrame(data)
-
- features = extract_features_from_dataframe(df, window_size=3)
-
- # Check shape
- assert features.shape[0] == 5, "Should have 5 feature vectors"
- assert features.shape[1] == 20, "Should have 20 features per vector"
-
- # Check that features are computed
- assert np.all(np.isfinite(features)), "All features should be finite"
-
- def test_get_feature_names(self):
- """Test that feature names are returned correctly."""
- feature_names = get_feature_names()
-
- assert len(feature_names) == 20, "Should have 20 feature names"
- assert 'cmd_vel_linear_x_mean' in feature_names
- assert 'imu_accel_x_mean' in feature_names
- assert 'cmd_linear_to_imu_accel_correlation' in feature_names
-
- def test_cross_features_correlation(self):
- """Test that cross-feature correlations are computed."""
- # Create perfectly correlated data
- cmd_vel_window = [
- [1.0, 0.0, 0.0, 0.0, 0.0, 0.5],
- [2.0, 0.0, 0.0, 0.0, 0.0, 1.0],
- [3.0, 0.0, 0.0, 0.0, 0.0, 1.5],
- ]
-
- imu_window = [
- [2.0, 0.0, 0.0, 0.0, 0.0, 1.0],
- [4.0, 0.0, 0.0, 0.0, 0.0, 2.0],
- [6.0, 0.0, 0.0, 0.0, 0.0, 3.0],
- ]
-
- features = extract_window_features(cmd_vel_window, imu_window)
-
- # Check correlation features (indices 16 and 17)
- # Should be close to 1.0 for perfectly correlated data
- assert features[16] > 0.99, "Linear correlation should be high"
- assert features[17] > 0.99, "Angular correlation should be high"
-
-
-if __name__ == '__main__':
- pytest.main([__file__, '-v'])
diff --git a/src/ros2_svdd_monitor/test/test_svdd_model.py b/src/ros2_svdd_monitor/test/test_svdd_model.py
deleted file mode 100644
index ed1f72c..0000000
--- a/src/ros2_svdd_monitor/test/test_svdd_model.py
+++ /dev/null
@@ -1,188 +0,0 @@
-"""
-Unit tests for SVDD model wrapper.
-"""
-
-import pytest
-import numpy as np
-import tempfile
-import os
-from ros2_svdd_monitor.svdd_model import SVDDModel
-
-
-class TestSVDDModel:
- """Test suite for SVDD model wrapper."""
-
- def test_model_initialization(self):
- """Test model initialization with default parameters."""
- model = SVDDModel()
-
- assert model.nu == 0.1
- assert model.gamma == 'scale'
- assert model.kernel == 'rbf'
- assert not model.is_fitted
-
- def test_model_initialization_custom(self):
- """Test model initialization with custom parameters."""
- model = SVDDModel(nu=0.2, gamma=0.5, kernel='rbf')
-
- assert model.nu == 0.2
- assert model.gamma == 0.5
- assert model.kernel == 'rbf'
-
- def test_model_fit(self):
- """Test model fitting."""
- # Generate simple training data
- np.random.seed(42)
- X_train = np.random.randn(100, 5)
-
- model = SVDDModel(nu=0.1)
- model.fit(X_train, scale=True)
-
- assert model.is_fitted
- assert model.scaler is not None
-
- def test_model_predict_before_fit(self):
- """Test that prediction fails before fitting."""
- model = SVDDModel()
- X_test = np.random.randn(10, 5)
-
- with pytest.raises(RuntimeError):
- model.predict(X_test)
-
- def test_model_predict(self):
- """Test model prediction."""
- # Generate training data (normal operation)
- np.random.seed(42)
- X_train = np.random.randn(100, 5) * 0.5 # Small variance
-
- # Train model
- model = SVDDModel(nu=0.1)
- model.fit(X_train, scale=True)
-
- # Test on normal data
- X_test_normal = np.random.randn(10, 5) * 0.5
- predictions = model.predict(X_test_normal, scale=True)
-
- assert len(predictions) == 10
- assert all(p in [-1, 1] for p in predictions)
-
- def test_model_decision_function(self):
- """Test model decision function."""
- # Generate training data
- np.random.seed(42)
- X_train = np.random.randn(100, 5)
-
- # Train model
- model = SVDDModel(nu=0.1)
- model.fit(X_train, scale=True)
-
- # Test decision function
- X_test = np.random.randn(10, 5)
- scores = model.decision_function(X_test, scale=True)
-
- assert len(scores) == 10
- assert all(np.isfinite(s) for s in scores)
-
- def test_model_save_load(self):
- """Test model save and load functionality."""
- # Generate training data
- np.random.seed(42)
- X_train = np.random.randn(100, 5)
-
- # Train model
- model = SVDDModel(nu=0.15, gamma=0.5)
- model.fit(X_train, scale=True)
-
- # Get prediction before saving
- X_test = np.random.randn(10, 5)
- predictions_before = model.predict(X_test, scale=True)
- scores_before = model.decision_function(X_test, scale=True)
-
- # Save model
- with tempfile.TemporaryDirectory() as tmpdir:
- model_path = os.path.join(tmpdir, 'test_model.pkl')
- scaler_path = os.path.join(tmpdir, 'test_scaler.pkl')
-
- model.save(model_path, scaler_path)
-
- # Load model
- model_loaded = SVDDModel()
- model_loaded.load(model_path, scaler_path)
-
- # Get prediction after loading
- predictions_after = model_loaded.predict(X_test, scale=True)
- scores_after = model_loaded.decision_function(X_test, scale=True)
-
- # Check that predictions are the same
- assert np.array_equal(predictions_before, predictions_after)
- assert np.allclose(scores_before, scores_after)
-
- # Check that model is marked as fitted
- assert model_loaded.is_fitted
-
- def test_model_save_before_fit(self):
- """Test that saving fails before fitting."""
- model = SVDDModel()
-
- with tempfile.TemporaryDirectory() as tmpdir:
- model_path = os.path.join(tmpdir, 'test_model.pkl')
-
- with pytest.raises(RuntimeError):
- model.save(model_path)
-
- def test_model_get_params(self):
- """Test getting model parameters."""
- model = SVDDModel(nu=0.2, gamma=0.5)
- params = model.get_params()
-
- assert params['nu'] == 0.2
- assert params['gamma'] == 0.5
- assert params['kernel'] == 'rbf'
- assert 'is_fitted' in params
-
- def test_model_outlier_detection(self):
- """Test that model can detect outliers."""
- # Generate normal data (clustered around origin)
- np.random.seed(42)
- X_train = np.random.randn(100, 5) * 0.5
-
- # Train model
- model = SVDDModel(nu=0.1)
- model.fit(X_train, scale=True)
-
- # Test on normal data
- X_test_normal = np.random.randn(10, 5) * 0.5
- predictions_normal = model.predict(X_test_normal, scale=True)
-
- # Test on outlier data (far from origin)
- X_test_outlier = np.random.randn(10, 5) * 10.0
- predictions_outlier = model.predict(X_test_outlier, scale=True)
-
- # Check that more outliers are detected in the outlier set
- normal_outliers = np.sum(predictions_normal == -1)
- outlier_outliers = np.sum(predictions_outlier == -1)
-
- # We expect more outliers in the outlier set
- # (This is a probabilistic test, so we use a lenient threshold)
- assert outlier_outliers >= normal_outliers
-
- def test_model_no_scaling(self):
- """Test model without feature scaling."""
- # Generate training data
- np.random.seed(42)
- X_train = np.random.randn(100, 5)
-
- # Train model without scaling
- model = SVDDModel(nu=0.1)
- model.fit(X_train, scale=False)
-
- # Predict without scaling
- X_test = np.random.randn(10, 5)
- predictions = model.predict(X_test, scale=False)
-
- assert len(predictions) == 10
- assert model.is_fitted
-
-
-if __name__ == '__main__':
- pytest.main([__file__, '-v'])
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/__init__.py b/svm_svdd/__init__.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/__init__.py
rename to svm_svdd/__init__.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/eval_svm_svdd.py b/svm_svdd/eval_svm_svdd.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/eval_svm_svdd.py
rename to svm_svdd/eval_svm_svdd.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/svdd_model.py b/svm_svdd/svdd_model.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/svdd_model.py
rename to svm_svdd/svdd_model.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/svm_svdd_model.py b/svm_svdd/svm_svdd_model.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/svm_svdd_model.py
rename to svm_svdd/svm_svdd_model.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/train.py b/svm_svdd/train.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/train.py
rename to svm_svdd/train.py
diff --git a/src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/train_svm_svdd.py b/svm_svdd/train_svm_svdd.py
similarity index 100%
rename from src/ros2_svdd_monitor/ros2_svdd_monitor/svm_svdd/train_svm_svdd.py
rename to svm_svdd/train_svm_svdd.py