Luis Yoichi Morales
commited on
Commit
·
c9ea516
1
Parent(s):
c099156
adding the ROS2 container and the playing and visualization scripts
Browse files- keypoint-db/.env +1 -0
- keypoint-db/Dockerfile +57 -0
- keypoint-db/Makefile +16 -0
- keypoint-db/README.md +181 -0
- keypoint-db/docker-compose.yml +23 -0
- keypoint-db/join_container.sh +5 -0
- keypoint-db/run_container.sh +51 -0
- keypoint-db/utils +2 -0
- keypoint-db/ws/compile_and_source.sh +6 -0
- keypoint-db/ws/src/db_loader/db_loader/__init__.py +1 -0
- keypoint-db/ws/src/db_loader/db_loader/index_keypoint_publisher.py +346 -0
- keypoint-db/ws/src/db_loader/db_loader/keypoint_publisher.py +630 -0
- keypoint-db/ws/src/db_loader/db_loader/layout_publisher.py +91 -0
- keypoint-db/ws/src/db_loader/db_loader/layout_visualizer.py +407 -0
- keypoint-db/ws/src/db_loader/launch/layout_visualization_launch.py +127 -0
- keypoint-db/ws/src/db_loader/package.xml +26 -0
- keypoint-db/ws/src/db_loader/resource/db_loader +0 -0
- keypoint-db/ws/src/db_loader/rviz/layout_view.rviz +278 -0
- keypoint-db/ws/src/db_loader/rviz/layout_view_rviz +133 -0
- keypoint-db/ws/src/db_loader/setup.cfg +4 -0
- keypoint-db/ws/src/db_loader/setup.py +40 -0
- keypoint-db/ws/src/db_loader/test/test_copyright.py +25 -0
- keypoint-db/ws/src/db_loader/test/test_flake8.py +25 -0
- keypoint-db/ws/src/db_loader/test/test_pep257.py +23 -0
- keypoint-db/ws/src/db_loader_msgs/CMakeLists.txt +21 -0
- keypoint-db/ws/src/db_loader_msgs/msg/Skeleton.msg +74 -0
- keypoint-db/ws/src/db_loader_msgs/package.xml +24 -0
keypoint-db/.env
ADDED
|
@@ -0,0 +1 @@
|
|
|
|
|
|
|
| 1 |
+
IMAGE_TAG=humble
|
keypoint-db/Dockerfile
ADDED
|
@@ -0,0 +1,57 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
ARG ROS2_DISTRO
|
| 2 |
+
FROM ros:${ROS2_DISTRO}-ros-core
|
| 3 |
+
|
| 4 |
+
ENV DEBIAN_FRONTEND=noninteractive
|
| 5 |
+
|
| 6 |
+
ARG APT_MIRROR="us"
|
| 7 |
+
RUN sed --in-place --regexp-extended "s|(//)(archive\.ubuntu)|\1${APT_MIRROR}.\2|" /etc/apt/sources.list
|
| 8 |
+
|
| 9 |
+
RUN apt-get update \
|
| 10 |
+
&& apt-get install -y --no-install-recommends \
|
| 11 |
+
bash-completion \
|
| 12 |
+
build-essential \
|
| 13 |
+
locate \
|
| 14 |
+
nano \
|
| 15 |
+
emacs \
|
| 16 |
+
python3-colcon-common-extensions \
|
| 17 |
+
python3-pip \
|
| 18 |
+
python3-rosdep \
|
| 19 |
+
sudo \
|
| 20 |
+
&& python3 -m pip install pydocstyle==6.1.1 \
|
| 21 |
+
&& python3 -m pip install pandas \
|
| 22 |
+
&& rosdep init \
|
| 23 |
+
&& apt-get install -y --no-install-recommends \
|
| 24 |
+
libeigen3-dev \
|
| 25 |
+
libpcl-dev \
|
| 26 |
+
libyaml-cpp-dev \
|
| 27 |
+
ros-${ROS_DISTRO}-diagnostic-updater \
|
| 28 |
+
ros-${ROS_DISTRO}-nav2-amcl \
|
| 29 |
+
ros-${ROS_DISTRO}-nav2-lifecycle-manager \
|
| 30 |
+
ros-${ROS_DISTRO}-nav2-map-server \
|
| 31 |
+
ros-${ROS_DISTRO}-nav2-rviz-plugins \
|
| 32 |
+
ros-${ROS_DISTRO}-pcl-conversions \
|
| 33 |
+
ros-${ROS_DISTRO}-pcl-msgs \
|
| 34 |
+
ros-${ROS_DISTRO}-rqt-image-view \
|
| 35 |
+
ros-${ROS_DISTRO}-rqt-graph \
|
| 36 |
+
ros-${ROS_DISTRO}-rviz2 \
|
| 37 |
+
ros-${ROS_DISTRO}-tf2 \
|
| 38 |
+
ros-${ROS_DISTRO}-tf2-geometry-msgs \
|
| 39 |
+
ros-${ROS_DISTRO}-tf2-sensor-msgs \
|
| 40 |
+
ros-${ROS_DISTRO}-tf2-eigen \
|
| 41 |
+
ros-${ROS_DISTRO}-v4l2-camera \
|
| 42 |
+
ros-${ROS_DISTRO}-pcl-ros \
|
| 43 |
+
|
| 44 |
+
&& rm -rf /var/lib/apt/lists/*
|
| 45 |
+
|
| 46 |
+
ARG USER_ID
|
| 47 |
+
ARG GROUP_ID
|
| 48 |
+
RUN addgroup --gid ${GROUP_ID} user \
|
| 49 |
+
&& adduser --disabled-password --gecos '' --uid ${USER_ID} --gid ${GROUP_ID} user \
|
| 50 |
+
&& usermod -a -G sudo,video user \
|
| 51 |
+
&& echo '%sudo ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers
|
| 52 |
+
|
| 53 |
+
USER user
|
| 54 |
+
RUN echo "source /opt/ros/${ROS_DISTRO}/setup.bash" >> /home/user/.bashrc \
|
| 55 |
+
&& echo "source /home/user/ws/install/setup.bash" >> /home/user/.bashrc
|
| 56 |
+
|
| 57 |
+
WORKDIR /home/user/ws
|
keypoint-db/Makefile
ADDED
|
@@ -0,0 +1,16 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
ROS2_DISTRO ?= $(shell cat .env | grep IMAGE_TAG | cut -d = -f 2)
|
| 2 |
+
IMAGE_NAME := ros2_devel
|
| 3 |
+
IMAGE_TAG = $(ROS2_DISTRO)
|
| 4 |
+
APT_MIRROR ?= jp
|
| 5 |
+
USER_ID :=$(shell id -u)
|
| 6 |
+
GROUP_ID :=$(shell id -g)
|
| 7 |
+
DOCKER_BUILD_OPTS ?=
|
| 8 |
+
|
| 9 |
+
.PHONY: build-image
|
| 10 |
+
build-image:
|
| 11 |
+
docker build $(DOCKER_BUILD_OPTS) \
|
| 12 |
+
-t $(IMAGE_NAME):$(IMAGE_TAG) \
|
| 13 |
+
--build-arg ROS2_DISTRO=$(ROS2_DISTRO) \
|
| 14 |
+
--build-arg APT_MIRROR=$(APT_MIRROR) \
|
| 15 |
+
--build-arg USER_ID=$(USER_ID) \
|
| 16 |
+
--build-arg GROUP_ID=$(GROUP_ID) .
|
keypoint-db/README.md
ADDED
|
@@ -0,0 +1,181 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
# ROS2 Docker Container Environment
|
| 2 |
+
|
| 3 |
+
A containerized ROS2 development environment with GUI support and NVIDIA GPU acceleration. This Docker setup provides an isolated workspace for ROS2 development while maintaining seamless integration with your host filesystem.
|
| 4 |
+
|
| 5 |
+
## Features
|
| 6 |
+
|
| 7 |
+
- **ROS2 Distribution**: Default `humble` (configurable)
|
| 8 |
+
- **GUI Support**: X11 forwarding for ROS2 GUI applications
|
| 9 |
+
- **GPU Support**: NVIDIA GPU acceleration (when available)
|
| 10 |
+
- **Workspace Mounting**: Host `ws/` directory mounted with full permissions
|
| 11 |
+
- **User Permissions**: Runs with matching host user/group IDs
|
| 12 |
+
- **Sample Movie**: [video](https://youtu.be/2pLzEvx31iA)
|
| 13 |
+
|
| 14 |
+
## Prerequisites
|
| 15 |
+
|
| 16 |
+
- **Docker**: Install following [Docker Engine installation guide](https://docs.docker.com/engine/install)
|
| 17 |
+
- **Post-install Setup**: Configure Docker for [non-root usage](https://docs.docker.com/engine/install/linux-postinstall)
|
| 18 |
+
- **NVIDIA Runtime** (optional): For GPU support, install [nvidia-container-toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html)
|
| 19 |
+
|
| 20 |
+
## Quick Start
|
| 21 |
+
|
| 22 |
+
1. **Clone and navigate to repository**
|
| 23 |
+
```bash
|
| 24 |
+
git clone git@github.com:Standard-Cognition/keypoint-db.git
|
| 25 |
+
cd keypoint_db
|
| 26 |
+
```
|
| 27 |
+
|
| 28 |
+
2. **Build the container**
|
| 29 |
+
```bash
|
| 30 |
+
make
|
| 31 |
+
```
|
| 32 |
+
|
| 33 |
+
3. **Create workspace**
|
| 34 |
+
```bash
|
| 35 |
+
mkdir -p ./ws/src
|
| 36 |
+
# Copy your ROS2 packages to ws/src/
|
| 37 |
+
```
|
| 38 |
+
|
| 39 |
+
4. **Run container**
|
| 40 |
+
```bash
|
| 41 |
+
./run_container.sh
|
| 42 |
+
```
|
| 43 |
+
|
| 44 |
+
5. **Join from another terminal** (optional)
|
| 45 |
+
```bash
|
| 46 |
+
./join_container.sh
|
| 47 |
+
```
|
| 48 |
+
|
| 49 |
+
## Detailed Usage
|
| 50 |
+
|
| 51 |
+
### Building the Container
|
| 52 |
+
|
| 53 |
+
**Basic build:**
|
| 54 |
+
```bash
|
| 55 |
+
make
|
| 56 |
+
```
|
| 57 |
+
|
| 58 |
+
**Custom ROS2 distribution:**
|
| 59 |
+
```bash
|
| 60 |
+
ROS2_DISTRO=humble DOCKER_BUILD_OPTS="--no-cache" make
|
| 61 |
+
```
|
| 62 |
+
|
| 63 |
+
**Additional build options:**
|
| 64 |
+
```bash
|
| 65 |
+
DOCKER_BUILD_OPTS="--pull=true --no-cache" make
|
| 66 |
+
```
|
| 67 |
+
|
| 68 |
+
### Container Management
|
| 69 |
+
|
| 70 |
+
**Start main container:**
|
| 71 |
+
```bash
|
| 72 |
+
./run_container.sh
|
| 73 |
+
```
|
| 74 |
+
|
| 75 |
+
**Start with specific ROS2 distribution:**
|
| 76 |
+
```bash
|
| 77 |
+
./run_container.sh --distro humble
|
| 78 |
+
```
|
| 79 |
+
|
| 80 |
+
**Join running container from another terminal:**
|
| 81 |
+
```bash
|
| 82 |
+
./join_container.sh
|
| 83 |
+
```
|
| 84 |
+
|
| 85 |
+
**Alternative docker-compose method:**
|
| 86 |
+
```bash
|
| 87 |
+
docker compose run --rm --name ros2_devel_container ros2_dev_env bash
|
| 88 |
+
```
|
| 89 |
+
|
| 90 |
+
### ROS2 Development Workflow
|
| 91 |
+
|
| 92 |
+
Inside the container (`/home/user/ws`):
|
| 93 |
+
|
| 94 |
+
**Install dependencies (first time only):**
|
| 95 |
+
```bash
|
| 96 |
+
sudo apt-get update
|
| 97 |
+
rosdep update
|
| 98 |
+
rosdep install -i --from-path src --rosdistro ${ROS_DISTRO} -y
|
| 99 |
+
```
|
| 100 |
+
|
| 101 |
+
**Build workspace:**
|
| 102 |
+
```bash
|
| 103 |
+
colcon build
|
| 104 |
+
```
|
| 105 |
+
|
| 106 |
+
**Source workspace:**
|
| 107 |
+
```bash
|
| 108 |
+
source install/setup.bash
|
| 109 |
+
```
|
| 110 |
+
|
| 111 |
+
**Run tests:**
|
| 112 |
+
```bash
|
| 113 |
+
colcon test
|
| 114 |
+
colcon test-result --all
|
| 115 |
+
```
|
| 116 |
+
|
| 117 |
+
## Project Structure
|
| 118 |
+
|
| 119 |
+
```
|
| 120 |
+
dataset_ros2_container/
|
| 121 |
+
├── Dockerfile # Container image definition
|
| 122 |
+
├── Makefile # Build automation
|
| 123 |
+
├── docker-compose.yml # Docker Compose configuration
|
| 124 |
+
├── .env # Environment variables
|
| 125 |
+
├── utils # Shared shell utilities
|
| 126 |
+
├── run_container.sh # Start container script
|
| 127 |
+
├── join_container.sh # Join running container script
|
| 128 |
+
├── ws/ # ROS2 workspace (mounted)
|
| 129 |
+
│ ├── src/ # Your ROS2 packages
|
| 130 |
+
│ ├── build/ # Build artifacts
|
| 131 |
+
│ ├── install/ # Installation directory
|
| 132 |
+
│ └── log/ # Build logs
|
| 133 |
+
└── README.md # This file
|
| 134 |
+
```
|
| 135 |
+
|
| 136 |
+
## Configuration
|
| 137 |
+
|
| 138 |
+
### Environment Variables
|
| 139 |
+
|
| 140 |
+
- `ROS2_DISTRO`: ROS2 distribution (default: from `.env` file)
|
| 141 |
+
- `IMAGE_NAME`: Docker image name (default: `ros2_devel`)
|
| 142 |
+
- `APT_MIRROR`: APT mirror location (default: `jp`)
|
| 143 |
+
- `DOCKER_BUILD_OPTS`: Additional Docker build options
|
| 144 |
+
|
| 145 |
+
### Container Features
|
| 146 |
+
|
| 147 |
+
- **X11 Forwarding**: Automatic GUI application support
|
| 148 |
+
- **NVIDIA GPU**: Auto-detected and enabled when available
|
| 149 |
+
- **Network**: Host networking for ROS2 communication
|
| 150 |
+
- **Workspace Persistence**: `ws/` directory changes persist on host
|
| 151 |
+
|
| 152 |
+
## Troubleshooting
|
| 153 |
+
|
| 154 |
+
**GPU not detected:**
|
| 155 |
+
- Ensure NVIDIA drivers are installed on host
|
| 156 |
+
- Install nvidia-container-toolkit
|
| 157 |
+
- Verify with `nvidia-smi` command
|
| 158 |
+
|
| 159 |
+
**Permission issues:**
|
| 160 |
+
- Container runs with host user/group IDs automatically
|
| 161 |
+
- Ensure Docker post-install steps completed
|
| 162 |
+
|
| 163 |
+
**GUI applications not working:**
|
| 164 |
+
- Verify X11 forwarding: `echo $DISPLAY`
|
| 165 |
+
- Check XAUTH permissions in container
|
| 166 |
+
|
| 167 |
+
**Build failures:**
|
| 168 |
+
- Use `--no-cache` build option
|
| 169 |
+
- Update base images with `--pull=true`
|
| 170 |
+
|
| 171 |
+
## Contributing
|
| 172 |
+
|
| 173 |
+
1. Fork the repository
|
| 174 |
+
2. Create feature branch: `git checkout -b feature-name`
|
| 175 |
+
3. Commit changes: `git commit -am 'Add feature'`
|
| 176 |
+
4. Push branch: `git push origin feature-name`
|
| 177 |
+
5. Submit pull request
|
| 178 |
+
|
| 179 |
+
## License
|
| 180 |
+
|
| 181 |
+
See [LICENSE](LICENSE) file for details.
|
keypoint-db/docker-compose.yml
ADDED
|
@@ -0,0 +1,23 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version: '3.5'
|
| 2 |
+
services:
|
| 3 |
+
ros2_dev_env:
|
| 4 |
+
image: ros2_devel:${IMAGE_TAG}
|
| 5 |
+
network_mode: host
|
| 6 |
+
environment:
|
| 7 |
+
- NVIDIA_VISIBLE_DEVICES=all
|
| 8 |
+
- NVIDIA_DRIVER_CAPABILITIES=all
|
| 9 |
+
- DISPLAY
|
| 10 |
+
# force libGL to use the NVIDIA GPU
|
| 11 |
+
- __NV_PRIME_RENDER_OFFLOAD=1
|
| 12 |
+
- __GLX_VENDOR_LIBRARY_NAME=nvidia
|
| 13 |
+
volumes:
|
| 14 |
+
- /tmp/.X11-unix:/tmp/.X11-unix:rw
|
| 15 |
+
- ./ws:/home/user/ws
|
| 16 |
+
tty: true
|
| 17 |
+
deploy:
|
| 18 |
+
resources:
|
| 19 |
+
reservations:
|
| 20 |
+
devices:
|
| 21 |
+
- driver: nvidia
|
| 22 |
+
count: 1
|
| 23 |
+
capabilities: [gpu]
|
keypoint-db/join_container.sh
ADDED
|
@@ -0,0 +1,5 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env bash
|
| 2 |
+
|
| 3 |
+
source utils
|
| 4 |
+
|
| 5 |
+
exec docker exec -it ${CONTAINER_NAME} bash
|
keypoint-db/run_container.sh
ADDED
|
@@ -0,0 +1,51 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env bash
|
| 2 |
+
|
| 3 |
+
source utils
|
| 4 |
+
|
| 5 |
+
IMAGE_TAG=$(cat .env | grep IMAGE_TAG | cut -d = -f 2)
|
| 6 |
+
|
| 7 |
+
while [[ ${#} -gt 0 ]]; do
|
| 8 |
+
key="${1}"
|
| 9 |
+
|
| 10 |
+
case ${key} in
|
| 11 |
+
-d|--distro)
|
| 12 |
+
IMAGE_TAG="${2}"
|
| 13 |
+
shift
|
| 14 |
+
shift
|
| 15 |
+
;;
|
| 16 |
+
*)
|
| 17 |
+
echo -e "\e[33mIgnoring unknown option ${key}.\e[0m"
|
| 18 |
+
exit 1
|
| 19 |
+
;;
|
| 20 |
+
esac
|
| 21 |
+
done
|
| 22 |
+
|
| 23 |
+
XSOCK=/tmp/.X11-unix
|
| 24 |
+
XAUTH=/tmp/.docker.xauth
|
| 25 |
+
touch ${XAUTH}
|
| 26 |
+
xauth nlist ${DISPLAY} | sed -e 's/^..../ffff/' | xauth -f ${XAUTH} nmerge -
|
| 27 |
+
|
| 28 |
+
DOCKER_ARGS_GUI="-e DISPLAY "
|
| 29 |
+
DOCKER_ARGS_GUI+="-e XAUTHORITY=${XAUTH} "
|
| 30 |
+
DOCKER_ARGS_GUI+="-v ${XAUTH}:${XAUTH}:rw "
|
| 31 |
+
DOCKER_ARGS_GUI+="-v ${XSOCK}:${XSOCK}:rw "
|
| 32 |
+
|
| 33 |
+
if command -v nvidia-smi &> /dev/null; then
|
| 34 |
+
gpu_list=$(nvidia-smi -L)
|
| 35 |
+
if [[ ! -z ${gpu_list} ]]; then
|
| 36 |
+
DOCKER_ARGS_GUI+="-e NVIDIA_DRIVER_CAPABILITIES=all "
|
| 37 |
+
DOCKER_ARGS_GUI+="--gpus=all "
|
| 38 |
+
else
|
| 39 |
+
echo -e "\e[33m[WARN]: Cannot find any GPU.\e[0m"
|
| 40 |
+
fi
|
| 41 |
+
fi
|
| 42 |
+
|
| 43 |
+
echo "Starting container using ${IMAGE_NAME}:${IMAGE_TAG}"
|
| 44 |
+
|
| 45 |
+
exec docker run -it --rm --name=${CONTAINER_NAME} \
|
| 46 |
+
--net=host \
|
| 47 |
+
--device=/dev/video0 \
|
| 48 |
+
${DOCKER_ARGS_GUI} \
|
| 49 |
+
-v $(pwd)/ws:/home/user/ws \
|
| 50 |
+
${IMAGE_NAME}:${IMAGE_TAG} \
|
| 51 |
+
bash
|
keypoint-db/utils
ADDED
|
@@ -0,0 +1,2 @@
|
|
|
|
|
|
|
|
|
|
| 1 |
+
IMAGE_NAME=$(cat Makefile | grep IMAGE_NAME | head -1 | cut -d "=" -f2 | tr -d '[:space:]')
|
| 2 |
+
CONTAINER_NAME=${IMAGE_NAME}_container
|
keypoint-db/ws/compile_and_source.sh
ADDED
|
@@ -0,0 +1,6 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env bash
|
| 2 |
+
|
| 3 |
+
colcon build --parallel-workers 10
|
| 4 |
+
source /home/user/ws/install/setup.bash
|
| 5 |
+
|
| 6 |
+
echo "sourced" /home/user/ws/install/setup.bash
|
keypoint-db/ws/src/db_loader/db_loader/__init__.py
ADDED
|
@@ -0,0 +1 @@
|
|
|
|
|
|
|
| 1 |
+
# ROS2 db_loader package
|
keypoint-db/ws/src/db_loader/db_loader/index_keypoint_publisher.py
ADDED
|
@@ -0,0 +1,346 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
|
| 3 |
+
import rclpy
|
| 4 |
+
from rclpy.node import Node
|
| 5 |
+
from db_loader_msgs.msg import Skeleton
|
| 6 |
+
import pandas as pd
|
| 7 |
+
import argparse
|
| 8 |
+
from pathlib import Path
|
| 9 |
+
|
| 10 |
+
|
| 11 |
+
class IndexKeypointPublisher(Node):
|
| 12 |
+
def __init__(self, index_file_path, num_chunks=20, playback_speed=1.0):
|
| 13 |
+
super().__init__('index_keypoint_publisher')
|
| 14 |
+
|
| 15 |
+
self.publisher = self.create_publisher(
|
| 16 |
+
Skeleton,
|
| 17 |
+
'skeleton_data',
|
| 18 |
+
10
|
| 19 |
+
)
|
| 20 |
+
|
| 21 |
+
self.playback_speed = playback_speed
|
| 22 |
+
self.num_chunks = num_chunks
|
| 23 |
+
self.previous_persons = set()
|
| 24 |
+
|
| 25 |
+
# Get directory containing the index file
|
| 26 |
+
self.data_dir = Path(index_file_path).parent
|
| 27 |
+
|
| 28 |
+
# Read the index file
|
| 29 |
+
try:
|
| 30 |
+
self.index_df = pd.read_csv(index_file_path)
|
| 31 |
+
self.get_logger().info(f'Successfully loaded index file: {len(self.index_df)} tracks')
|
| 32 |
+
|
| 33 |
+
# Validate required columns
|
| 34 |
+
required_cols = ['track_id', 'track_start_timestamp', 'track_end_timestamp']
|
| 35 |
+
missing_cols = [col for col in required_cols if col not in self.index_df.columns]
|
| 36 |
+
if missing_cols:
|
| 37 |
+
self.get_logger().error(f'Missing required columns in index: {missing_cols}')
|
| 38 |
+
self.index_df = None
|
| 39 |
+
return
|
| 40 |
+
|
| 41 |
+
# Parse timestamps
|
| 42 |
+
self.index_df['track_start_timestamp'] = pd.to_datetime(
|
| 43 |
+
self.index_df['track_start_timestamp'], format='ISO8601'
|
| 44 |
+
)
|
| 45 |
+
self.index_df['track_end_timestamp'] = pd.to_datetime(
|
| 46 |
+
self.index_df['track_end_timestamp'], format='ISO8601'
|
| 47 |
+
)
|
| 48 |
+
|
| 49 |
+
# Calculate global time range
|
| 50 |
+
global_start = self.index_df['track_start_timestamp'].min()
|
| 51 |
+
global_end = self.index_df['track_end_timestamp'].max()
|
| 52 |
+
|
| 53 |
+
# Convert to seconds from global start
|
| 54 |
+
self.index_df['start_seconds'] = (
|
| 55 |
+
self.index_df['track_start_timestamp'] - global_start
|
| 56 |
+
).dt.total_seconds()
|
| 57 |
+
self.index_df['end_seconds'] = (
|
| 58 |
+
self.index_df['track_end_timestamp'] - global_start
|
| 59 |
+
).dt.total_seconds()
|
| 60 |
+
|
| 61 |
+
# Store timing information
|
| 62 |
+
self.global_start_timestamp = global_start
|
| 63 |
+
self.start_time = 0.0
|
| 64 |
+
self.end_time = float((global_end - global_start).total_seconds())
|
| 65 |
+
self.current_time = self.start_time
|
| 66 |
+
|
| 67 |
+
self.get_logger().info(f'Global time range: {self.start_time:.2f} to {self.end_time:.2f} seconds')
|
| 68 |
+
self.get_logger().info(f'Total duration: {self.end_time:.2f} seconds ({self.end_time/60:.1f} minutes)')
|
| 69 |
+
|
| 70 |
+
# Calculate chunk boundaries
|
| 71 |
+
self.chunk_duration = self.end_time / num_chunks
|
| 72 |
+
self.chunks = []
|
| 73 |
+
for i in range(num_chunks):
|
| 74 |
+
chunk_start = i * self.chunk_duration
|
| 75 |
+
chunk_end = (i + 1) * self.chunk_duration if i < num_chunks - 1 else self.end_time
|
| 76 |
+
self.chunks.append({
|
| 77 |
+
'start': chunk_start,
|
| 78 |
+
'end': chunk_end,
|
| 79 |
+
'data': None,
|
| 80 |
+
'loaded': False
|
| 81 |
+
})
|
| 82 |
+
|
| 83 |
+
self.get_logger().info(f'Created {num_chunks} chunks of {self.chunk_duration:.1f}s each')
|
| 84 |
+
|
| 85 |
+
# Current chunk index
|
| 86 |
+
self.current_chunk_idx = 0
|
| 87 |
+
self.current_chunk_data = None
|
| 88 |
+
|
| 89 |
+
# Load first chunk
|
| 90 |
+
self.load_chunk(0)
|
| 91 |
+
|
| 92 |
+
# Create timer for playback (30 Hz)
|
| 93 |
+
self.update_rate = 30.0
|
| 94 |
+
self.timer = self.create_timer(1.0 / self.update_rate, self.publish_callback)
|
| 95 |
+
self.get_logger().info(f'Starting playback at {playback_speed}x speed')
|
| 96 |
+
|
| 97 |
+
except FileNotFoundError:
|
| 98 |
+
self.get_logger().error(f'Index file not found: {index_file_path}')
|
| 99 |
+
self.index_df = None
|
| 100 |
+
except Exception as e:
|
| 101 |
+
self.get_logger().error(f'Failed to load index file: {e}')
|
| 102 |
+
import traceback
|
| 103 |
+
self.get_logger().error(traceback.format_exc())
|
| 104 |
+
self.index_df = None
|
| 105 |
+
|
| 106 |
+
def load_chunk(self, chunk_idx):
|
| 107 |
+
"""Load and merge all tracks that overlap with this chunk"""
|
| 108 |
+
if chunk_idx >= len(self.chunks):
|
| 109 |
+
return False
|
| 110 |
+
|
| 111 |
+
chunk = self.chunks[chunk_idx]
|
| 112 |
+
chunk_start = chunk['start']
|
| 113 |
+
chunk_end = chunk['end']
|
| 114 |
+
|
| 115 |
+
self.get_logger().info(f'Loading chunk {chunk_idx}: time {chunk_start:.1f}s to {chunk_end:.1f}s')
|
| 116 |
+
|
| 117 |
+
# Find all tracks that overlap with this chunk
|
| 118 |
+
overlapping_tracks = self.index_df[
|
| 119 |
+
(self.index_df['start_seconds'] < chunk_end) &
|
| 120 |
+
(self.index_df['end_seconds'] > chunk_start)
|
| 121 |
+
]
|
| 122 |
+
|
| 123 |
+
self.get_logger().info(f'Found {len(overlapping_tracks)} tracks overlapping with chunk {chunk_idx}')
|
| 124 |
+
|
| 125 |
+
# Load and merge all overlapping tracks
|
| 126 |
+
all_track_data = []
|
| 127 |
+
|
| 128 |
+
for _, track_row in overlapping_tracks.iterrows():
|
| 129 |
+
track_id = str(track_row['track_id'])
|
| 130 |
+
csv_path = self.data_dir / f'track_{track_id}.csv'
|
| 131 |
+
|
| 132 |
+
try:
|
| 133 |
+
df = pd.read_csv(csv_path)
|
| 134 |
+
|
| 135 |
+
# Parse timestamps
|
| 136 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'], format='ISO8601')
|
| 137 |
+
|
| 138 |
+
# Convert to seconds from global start
|
| 139 |
+
df['time_seconds'] = (df['timestamp'] - self.global_start_timestamp).dt.total_seconds()
|
| 140 |
+
|
| 141 |
+
# Filter to only include data within this chunk (with small buffer)
|
| 142 |
+
buffer = 1.0 # 1 second buffer on each side
|
| 143 |
+
chunk_data = df[
|
| 144 |
+
(df['time_seconds'] >= chunk_start - buffer) &
|
| 145 |
+
(df['time_seconds'] <= chunk_end + buffer)
|
| 146 |
+
]
|
| 147 |
+
|
| 148 |
+
if not chunk_data.empty:
|
| 149 |
+
all_track_data.append(chunk_data)
|
| 150 |
+
self.get_logger().debug(f' Track {track_id}: loaded {len(chunk_data)} rows')
|
| 151 |
+
|
| 152 |
+
except Exception as e:
|
| 153 |
+
self.get_logger().error(f'Failed to load track {track_id}: {e}')
|
| 154 |
+
|
| 155 |
+
if all_track_data:
|
| 156 |
+
# Merge all track data into single dataframe
|
| 157 |
+
merged_df = pd.concat(all_track_data, ignore_index=True)
|
| 158 |
+
|
| 159 |
+
# Sort by time
|
| 160 |
+
merged_df = merged_df.sort_values('time_seconds').reset_index(drop=True)
|
| 161 |
+
|
| 162 |
+
chunk['data'] = merged_df
|
| 163 |
+
chunk['loaded'] = True
|
| 164 |
+
|
| 165 |
+
self.get_logger().info(
|
| 166 |
+
f'Chunk {chunk_idx} loaded: {len(merged_df)} total rows, '
|
| 167 |
+
f'time range: {merged_df["time_seconds"].min():.2f} to {merged_df["time_seconds"].max():.2f}s'
|
| 168 |
+
)
|
| 169 |
+
return True
|
| 170 |
+
else:
|
| 171 |
+
self.get_logger().warning(f'No data found for chunk {chunk_idx}')
|
| 172 |
+
chunk['loaded'] = True # Mark as loaded even if empty
|
| 173 |
+
return False
|
| 174 |
+
|
| 175 |
+
def publish_callback(self):
|
| 176 |
+
if self.index_df is None:
|
| 177 |
+
return
|
| 178 |
+
|
| 179 |
+
# Check if we need to switch to next chunk
|
| 180 |
+
if self.current_time >= self.chunks[self.current_chunk_idx]['end']:
|
| 181 |
+
self.get_logger().info(f'Finished chunk {self.current_chunk_idx}')
|
| 182 |
+
|
| 183 |
+
# Unload current chunk to free memory
|
| 184 |
+
self.chunks[self.current_chunk_idx]['data'] = None
|
| 185 |
+
|
| 186 |
+
# Move to next chunk
|
| 187 |
+
self.current_chunk_idx += 1
|
| 188 |
+
|
| 189 |
+
if self.current_chunk_idx >= len(self.chunks):
|
| 190 |
+
# Reached end, loop back
|
| 191 |
+
self.get_logger().info('Playback finished. Looping...')
|
| 192 |
+
self.current_chunk_idx = 0
|
| 193 |
+
self.current_time = self.start_time
|
| 194 |
+
self.previous_persons = set()
|
| 195 |
+
self.load_chunk(0)
|
| 196 |
+
else:
|
| 197 |
+
# Load next chunk if not already loaded
|
| 198 |
+
if not self.chunks[self.current_chunk_idx]['loaded']:
|
| 199 |
+
self.load_chunk(self.current_chunk_idx)
|
| 200 |
+
|
| 201 |
+
# Preload next chunk when we're near the end of current chunk
|
| 202 |
+
preload_threshold = 5.0 # Preload 5 seconds before end
|
| 203 |
+
if (self.current_chunk_idx < len(self.chunks) - 1 and
|
| 204 |
+
self.current_time >= self.chunks[self.current_chunk_idx]['end'] - preload_threshold):
|
| 205 |
+
next_chunk_idx = self.current_chunk_idx + 1
|
| 206 |
+
if not self.chunks[next_chunk_idx]['loaded']:
|
| 207 |
+
self.get_logger().info(f'Preloading chunk {next_chunk_idx}')
|
| 208 |
+
self.load_chunk(next_chunk_idx)
|
| 209 |
+
|
| 210 |
+
# Get current chunk data
|
| 211 |
+
current_chunk = self.chunks[self.current_chunk_idx]
|
| 212 |
+
if current_chunk['data'] is None or current_chunk['data'].empty:
|
| 213 |
+
# No data, just advance time
|
| 214 |
+
time_step = (1.0 / self.update_rate) * self.playback_speed
|
| 215 |
+
self.current_time += time_step
|
| 216 |
+
return
|
| 217 |
+
|
| 218 |
+
df = current_chunk['data']
|
| 219 |
+
|
| 220 |
+
# Get all data points at current time (with small time window)
|
| 221 |
+
time_window = 0.033 # ~30ms window (one frame at 30Hz)
|
| 222 |
+
current_data = df[
|
| 223 |
+
(df['time_seconds'] >= self.current_time) &
|
| 224 |
+
(df['time_seconds'] < self.current_time + time_window)
|
| 225 |
+
]
|
| 226 |
+
|
| 227 |
+
current_persons = set()
|
| 228 |
+
|
| 229 |
+
if not current_data.empty:
|
| 230 |
+
# Publish a message for each person at this timestamp
|
| 231 |
+
for idx, row in current_data.iterrows():
|
| 232 |
+
person_id = str(row['person_track_id'])
|
| 233 |
+
current_persons.add(person_id)
|
| 234 |
+
|
| 235 |
+
msg = Skeleton()
|
| 236 |
+
|
| 237 |
+
# Basic info
|
| 238 |
+
msg.person_track_id = person_id
|
| 239 |
+
msg.timestamp = float(row['time_seconds'])
|
| 240 |
+
|
| 241 |
+
# Define all keypoint fields
|
| 242 |
+
keypoint_fields = [
|
| 243 |
+
'neck_x', 'neck_y', 'neck_z',
|
| 244 |
+
'right_shoulder_x', 'right_shoulder_y', 'right_shoulder_z',
|
| 245 |
+
'right_elbow_x', 'right_elbow_y', 'right_elbow_z',
|
| 246 |
+
'right_wrist_x', 'right_wrist_y', 'right_wrist_z',
|
| 247 |
+
'right_hand_x', 'right_hand_y', 'right_hand_z',
|
| 248 |
+
'left_shoulder_x', 'left_shoulder_y', 'left_shoulder_z',
|
| 249 |
+
'left_elbow_x', 'left_elbow_y', 'left_elbow_z',
|
| 250 |
+
'left_wrist_x', 'left_wrist_y', 'left_wrist_z',
|
| 251 |
+
'left_hand_x', 'left_hand_y', 'left_hand_z',
|
| 252 |
+
'middle_of_waist_x', 'middle_of_waist_y', 'middle_of_waist_z',
|
| 253 |
+
'right_hip_x', 'right_hip_y', 'right_hip_z',
|
| 254 |
+
'right_knee_x', 'right_knee_y', 'right_knee_z',
|
| 255 |
+
'right_ankle_x', 'right_ankle_y', 'right_ankle_z',
|
| 256 |
+
'right_foot_x', 'right_foot_y', 'right_foot_z',
|
| 257 |
+
'left_hip_x', 'left_hip_y', 'left_hip_z',
|
| 258 |
+
'left_knee_x', 'left_knee_y', 'left_knee_z',
|
| 259 |
+
'left_ankle_x', 'left_ankle_y', 'left_ankle_z',
|
| 260 |
+
'left_foot_x', 'left_foot_y', 'left_foot_z',
|
| 261 |
+
]
|
| 262 |
+
|
| 263 |
+
# Set all keypoint values
|
| 264 |
+
for field in keypoint_fields:
|
| 265 |
+
if field in row.index and pd.notna(row[field]):
|
| 266 |
+
setattr(msg, field, float(row[field]))
|
| 267 |
+
else:
|
| 268 |
+
setattr(msg, field, 0.0)
|
| 269 |
+
|
| 270 |
+
# Publish the message
|
| 271 |
+
self.publisher.publish(msg)
|
| 272 |
+
|
| 273 |
+
self.get_logger().debug(
|
| 274 |
+
f'Published {len(current_data)} skeleton messages at t={self.current_time:.2f}s '
|
| 275 |
+
f'(chunk {self.current_chunk_idx})'
|
| 276 |
+
)
|
| 277 |
+
|
| 278 |
+
# Publish empty messages for persons that left
|
| 279 |
+
persons_left = self.previous_persons - current_persons
|
| 280 |
+
for person_id in persons_left:
|
| 281 |
+
msg = Skeleton()
|
| 282 |
+
msg.person_track_id = person_id
|
| 283 |
+
msg.timestamp = -1.0
|
| 284 |
+
self.publisher.publish(msg)
|
| 285 |
+
self.get_logger().debug(f'Person {person_id} left the scene')
|
| 286 |
+
|
| 287 |
+
# Update previous persons
|
| 288 |
+
self.previous_persons = current_persons
|
| 289 |
+
|
| 290 |
+
# Advance time
|
| 291 |
+
time_step = (1.0 / self.update_rate) * self.playback_speed
|
| 292 |
+
self.current_time += time_step
|
| 293 |
+
|
| 294 |
+
# Log progress every 10 seconds
|
| 295 |
+
elapsed_time = self.current_time - self.start_time
|
| 296 |
+
if int(elapsed_time) % 10 == 0 and int(elapsed_time) != int(elapsed_time - time_step):
|
| 297 |
+
progress = elapsed_time / (self.end_time - self.start_time) * 100
|
| 298 |
+
self.get_logger().info(
|
| 299 |
+
f'Playback: {progress:.1f}% | Time: {elapsed_time:.1f}s | Chunk: {self.current_chunk_idx}/{len(self.chunks)}'
|
| 300 |
+
)
|
| 301 |
+
|
| 302 |
+
|
| 303 |
+
def main(args=None):
|
| 304 |
+
parser = argparse.ArgumentParser(
|
| 305 |
+
description='Publish skeleton keypoint data from indexed CSV files'
|
| 306 |
+
)
|
| 307 |
+
parser.add_argument(
|
| 308 |
+
'index_file',
|
| 309 |
+
type=str,
|
| 310 |
+
help='Path to the index CSV file (e.g., stats.csv)'
|
| 311 |
+
)
|
| 312 |
+
parser.add_argument(
|
| 313 |
+
'--chunks',
|
| 314 |
+
type=int,
|
| 315 |
+
default=20,
|
| 316 |
+
help='Number of time chunks to divide playback into (default: 20)'
|
| 317 |
+
)
|
| 318 |
+
parser.add_argument(
|
| 319 |
+
'--speed',
|
| 320 |
+
type=float,
|
| 321 |
+
default=1.0,
|
| 322 |
+
help='Playback speed multiplier (default: 1.0)'
|
| 323 |
+
)
|
| 324 |
+
|
| 325 |
+
import sys
|
| 326 |
+
filtered_args = [arg for arg in sys.argv[1:] if not arg.startswith('__')]
|
| 327 |
+
parsed_args, unknown = parser.parse_known_args(filtered_args)
|
| 328 |
+
|
| 329 |
+
rclpy.init(args=args)
|
| 330 |
+
node = IndexKeypointPublisher(
|
| 331 |
+
parsed_args.index_file,
|
| 332 |
+
parsed_args.chunks,
|
| 333 |
+
parsed_args.speed
|
| 334 |
+
)
|
| 335 |
+
|
| 336 |
+
try:
|
| 337 |
+
rclpy.spin(node)
|
| 338 |
+
except KeyboardInterrupt:
|
| 339 |
+
pass
|
| 340 |
+
finally:
|
| 341 |
+
node.destroy_node()
|
| 342 |
+
rclpy.shutdown()
|
| 343 |
+
|
| 344 |
+
|
| 345 |
+
if __name__ == '__main__':
|
| 346 |
+
main()
|
keypoint-db/ws/src/db_loader/db_loader/keypoint_publisher.py
ADDED
|
@@ -0,0 +1,630 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
|
| 3 |
+
import rclpy
|
| 4 |
+
from rclpy.node import Node
|
| 5 |
+
from visualization_msgs.msg import Marker, MarkerArray
|
| 6 |
+
from geometry_msgs.msg import Point
|
| 7 |
+
import pandas as pd
|
| 8 |
+
import numpy as np
|
| 9 |
+
import argparse
|
| 10 |
+
from pathlib import Path
|
| 11 |
+
|
| 12 |
+
|
| 13 |
+
class KeypointPublisher(Node):
|
| 14 |
+
def __init__(self, csv_file_path=None, index_file_path=None, playback_speed=1.0, publish_rate=30.0, interpolate=False):
|
| 15 |
+
super().__init__('keypoint_publisher')
|
| 16 |
+
|
| 17 |
+
# Publisher for visualization markers (increased queue size)
|
| 18 |
+
self.marker_pub = self.create_publisher(
|
| 19 |
+
MarkerArray,
|
| 20 |
+
'skeleton_markers',
|
| 21 |
+
100
|
| 22 |
+
)
|
| 23 |
+
|
| 24 |
+
self.playback_speed = playback_speed
|
| 25 |
+
self.interpolate = interpolate
|
| 26 |
+
self.previous_persons = set()
|
| 27 |
+
self.timeout = rclpy.duration.Duration(seconds=2.0)
|
| 28 |
+
|
| 29 |
+
# Chunk management
|
| 30 |
+
self.chunks = []
|
| 31 |
+
self.current_chunk_idx = 0
|
| 32 |
+
self.next_chunk_df = None
|
| 33 |
+
self.preload_threshold = 2.0
|
| 34 |
+
|
| 35 |
+
# Current data
|
| 36 |
+
self.df = None
|
| 37 |
+
self.current_time = 0.0
|
| 38 |
+
self.start_time = 0.0
|
| 39 |
+
self.end_time = 0.0
|
| 40 |
+
|
| 41 |
+
# Color management for persons
|
| 42 |
+
self.person_colors = {}
|
| 43 |
+
self.color_index = 0
|
| 44 |
+
|
| 45 |
+
# Keypoint fields for interpolation
|
| 46 |
+
self.keypoint_fields = [
|
| 47 |
+
'neck_x', 'neck_y', 'neck_z',
|
| 48 |
+
'right_shoulder_x', 'right_shoulder_y', 'right_shoulder_z',
|
| 49 |
+
'right_elbow_x', 'right_elbow_y', 'right_elbow_z',
|
| 50 |
+
'right_wrist_x', 'right_wrist_y', 'right_wrist_z',
|
| 51 |
+
'right_hand_x', 'right_hand_y', 'right_hand_z',
|
| 52 |
+
'left_shoulder_x', 'left_shoulder_y', 'left_shoulder_z',
|
| 53 |
+
'left_elbow_x', 'left_elbow_y', 'left_elbow_z',
|
| 54 |
+
'left_wrist_x', 'left_wrist_y', 'left_wrist_z',
|
| 55 |
+
'left_hand_x', 'left_hand_y', 'left_hand_z',
|
| 56 |
+
'middle_of_waist_x', 'middle_of_waist_y', 'middle_of_waist_z',
|
| 57 |
+
'right_hip_x', 'right_hip_y', 'right_hip_z',
|
| 58 |
+
'right_knee_x', 'right_knee_y', 'right_knee_z',
|
| 59 |
+
'right_ankle_x', 'right_ankle_y', 'right_ankle_z',
|
| 60 |
+
'right_foot_x', 'right_foot_y', 'right_foot_z',
|
| 61 |
+
'left_hip_x', 'left_hip_y', 'left_hip_z',
|
| 62 |
+
'left_knee_x', 'left_knee_y', 'left_knee_z',
|
| 63 |
+
'left_ankle_x', 'left_ankle_y', 'left_ankle_z',
|
| 64 |
+
'left_foot_x', 'left_foot_y', 'left_foot_z',
|
| 65 |
+
]
|
| 66 |
+
|
| 67 |
+
# Keypoint names for visualization
|
| 68 |
+
self.keypoint_names = [
|
| 69 |
+
'neck', 'right_shoulder', 'right_elbow', 'right_wrist', 'right_hand',
|
| 70 |
+
'left_shoulder', 'left_elbow', 'left_wrist', 'left_hand',
|
| 71 |
+
'middle_of_waist', 'right_hip', 'right_knee', 'right_ankle', 'right_foot',
|
| 72 |
+
'left_hip', 'left_knee', 'left_ankle', 'left_foot',
|
| 73 |
+
]
|
| 74 |
+
|
| 75 |
+
# Define skeleton connections (bones)
|
| 76 |
+
self.skeleton_connections = [
|
| 77 |
+
('neck', 'middle_of_waist'),
|
| 78 |
+
('neck', 'right_shoulder'),
|
| 79 |
+
('right_shoulder', 'right_elbow'),
|
| 80 |
+
('right_elbow', 'right_wrist'),
|
| 81 |
+
('right_wrist', 'right_hand'),
|
| 82 |
+
('neck', 'left_shoulder'),
|
| 83 |
+
('left_shoulder', 'left_elbow'),
|
| 84 |
+
('left_elbow', 'left_wrist'),
|
| 85 |
+
('left_wrist', 'left_hand'),
|
| 86 |
+
('middle_of_waist', 'right_hip'),
|
| 87 |
+
('right_hip', 'right_knee'),
|
| 88 |
+
('right_knee', 'right_ankle'),
|
| 89 |
+
('right_ankle', 'right_foot'),
|
| 90 |
+
('middle_of_waist', 'left_hip'),
|
| 91 |
+
('left_hip', 'left_knee'),
|
| 92 |
+
('left_knee', 'left_ankle'),
|
| 93 |
+
('left_ankle', 'left_foot'),
|
| 94 |
+
]
|
| 95 |
+
|
| 96 |
+
# Define which keypoints should be larger
|
| 97 |
+
self.large_keypoints = ['right_shoulder', 'left_shoulder']
|
| 98 |
+
|
| 99 |
+
# Initialize based on mode
|
| 100 |
+
if index_file_path:
|
| 101 |
+
self._init_multi_chunk_mode(index_file_path)
|
| 102 |
+
elif csv_file_path:
|
| 103 |
+
self._init_single_chunk_mode(csv_file_path)
|
| 104 |
+
else:
|
| 105 |
+
self.get_logger().error('Either csv_file or index_file must be provided')
|
| 106 |
+
return
|
| 107 |
+
|
| 108 |
+
if self.df is not None:
|
| 109 |
+
# Publish at specified rate
|
| 110 |
+
self.update_rate = publish_rate
|
| 111 |
+
self.timer = self.create_timer(1.0 / self.update_rate, self.publish_callback)
|
| 112 |
+
self.get_logger().info(f'Starting playback at {playback_speed}x speed')
|
| 113 |
+
self.get_logger().info(f'Publishing markers at {publish_rate} Hz')
|
| 114 |
+
self.get_logger().info(f'Interpolation: {"ENABLED" if self.interpolate else "DISABLED"}')
|
| 115 |
+
|
| 116 |
+
def _generate_color(self):
|
| 117 |
+
"""Generate a distinct color for each person"""
|
| 118 |
+
hue = (self.color_index * 0.618033988749895) % 1.0
|
| 119 |
+
self.color_index += 1
|
| 120 |
+
|
| 121 |
+
h = hue * 6
|
| 122 |
+
x = 1.0 - abs((h % 2) - 1.0)
|
| 123 |
+
|
| 124 |
+
if h < 1: r, g, b = 1.0, x, 0.0
|
| 125 |
+
elif h < 2: r, g, b = x, 1.0, 0.0
|
| 126 |
+
elif h < 3: r, g, b = 0.0, 1.0, x
|
| 127 |
+
elif h < 4: r, g, b = 0.0, x, 1.0
|
| 128 |
+
elif h < 5: r, g, b = x, 0.0, 1.0
|
| 129 |
+
else: r, g, b = 1.0, 0.0, x
|
| 130 |
+
|
| 131 |
+
return (r, g, b)
|
| 132 |
+
|
| 133 |
+
def _get_nearest_frame(self, person_id, current_time):
|
| 134 |
+
"""Get the nearest frame for a person at the current time (no interpolation)"""
|
| 135 |
+
# Get data for this person
|
| 136 |
+
person_data = self.df[self.df['person_track_id'] == person_id].copy()
|
| 137 |
+
|
| 138 |
+
if len(person_data) == 0:
|
| 139 |
+
return None
|
| 140 |
+
|
| 141 |
+
# Find the nearest timestamp
|
| 142 |
+
person_data = person_data.sort_values('time_seconds')
|
| 143 |
+
times = person_data['time_seconds'].values
|
| 144 |
+
|
| 145 |
+
# Find the index of the closest time
|
| 146 |
+
idx = np.argmin(np.abs(times - current_time))
|
| 147 |
+
|
| 148 |
+
return person_data.iloc[idx]
|
| 149 |
+
|
| 150 |
+
def _interpolate_skeleton(self, person_id, current_time):
|
| 151 |
+
"""Interpolate skeleton keypoints for a person at the current time"""
|
| 152 |
+
# Get data for this person
|
| 153 |
+
person_data = self.df[self.df['person_track_id'] == person_id].copy()
|
| 154 |
+
|
| 155 |
+
if len(person_data) == 0:
|
| 156 |
+
return None
|
| 157 |
+
|
| 158 |
+
# Find the two nearest timestamps (before and after current_time)
|
| 159 |
+
person_data = person_data.sort_values('time_seconds')
|
| 160 |
+
times = person_data['time_seconds'].values
|
| 161 |
+
|
| 162 |
+
# Find interpolation indices
|
| 163 |
+
if current_time <= times[0]:
|
| 164 |
+
# Before first point, use first frame
|
| 165 |
+
return person_data.iloc[0]
|
| 166 |
+
elif current_time >= times[-1]:
|
| 167 |
+
# After last point, use last frame
|
| 168 |
+
return person_data.iloc[-1]
|
| 169 |
+
else:
|
| 170 |
+
# Interpolate between two frames
|
| 171 |
+
idx_after = np.searchsorted(times, current_time)
|
| 172 |
+
idx_before = idx_after - 1
|
| 173 |
+
|
| 174 |
+
time_before = times[idx_before]
|
| 175 |
+
time_after = times[idx_after]
|
| 176 |
+
|
| 177 |
+
# Calculate interpolation weight
|
| 178 |
+
alpha = (current_time - time_before) / (time_after - time_before)
|
| 179 |
+
|
| 180 |
+
# Get the two frames
|
| 181 |
+
frame_before = person_data.iloc[idx_before]
|
| 182 |
+
frame_after = person_data.iloc[idx_after]
|
| 183 |
+
|
| 184 |
+
# Create interpolated frame
|
| 185 |
+
interpolated = frame_before.copy()
|
| 186 |
+
interpolated['time_seconds'] = current_time
|
| 187 |
+
|
| 188 |
+
# Interpolate all keypoint fields
|
| 189 |
+
for field in self.keypoint_fields:
|
| 190 |
+
if field in frame_before.index and field in frame_after.index:
|
| 191 |
+
val_before = frame_before[field]
|
| 192 |
+
val_after = frame_after[field]
|
| 193 |
+
|
| 194 |
+
# Only interpolate if both values are valid (not NaN and not 0)
|
| 195 |
+
if pd.notna(val_before) and pd.notna(val_after):
|
| 196 |
+
if val_before != 0.0 or val_after != 0.0:
|
| 197 |
+
interpolated[field] = val_before * (1 - alpha) + val_after * alpha
|
| 198 |
+
|
| 199 |
+
return interpolated
|
| 200 |
+
|
| 201 |
+
def _get_frame_for_person(self, person_id, current_time):
|
| 202 |
+
"""Get frame for person - either nearest or interpolated based on settings"""
|
| 203 |
+
if self.interpolate:
|
| 204 |
+
return self._interpolate_skeleton(person_id, current_time)
|
| 205 |
+
else:
|
| 206 |
+
return self._get_nearest_frame(person_id, current_time)
|
| 207 |
+
|
| 208 |
+
def _get_keypoint_position(self, frame, keypoint_name):
|
| 209 |
+
"""Extract (x, y, z) position for a given keypoint from frame"""
|
| 210 |
+
x = frame.get(f'{keypoint_name}_x', 0.0)
|
| 211 |
+
y = frame.get(f'{keypoint_name}_y', 0.0)
|
| 212 |
+
z = frame.get(f'{keypoint_name}_z', 0.0)
|
| 213 |
+
|
| 214 |
+
if pd.isna(x) or pd.isna(y) or pd.isna(z):
|
| 215 |
+
return None
|
| 216 |
+
if x == 0.0 and y == 0.0 and z == 0.0:
|
| 217 |
+
return None
|
| 218 |
+
|
| 219 |
+
return (float(x), float(y), float(z))
|
| 220 |
+
|
| 221 |
+
def _create_markers_for_person(self, person_id, frame, publish_timestamp):
|
| 222 |
+
"""Create all markers (keypoints, bones, labels) for a single person"""
|
| 223 |
+
markers = []
|
| 224 |
+
|
| 225 |
+
if person_id not in self.person_colors:
|
| 226 |
+
self.person_colors[person_id] = self._generate_color()
|
| 227 |
+
self.get_logger().info(f'New person detected: {person_id}')
|
| 228 |
+
|
| 229 |
+
color = self.person_colors[person_id]
|
| 230 |
+
marker_id_counter = 0
|
| 231 |
+
|
| 232 |
+
# Extract all keypoint positions
|
| 233 |
+
keypoint_positions = {}
|
| 234 |
+
for keypoint_name in self.keypoint_names:
|
| 235 |
+
pos = self._get_keypoint_position(frame, keypoint_name)
|
| 236 |
+
if pos is not None:
|
| 237 |
+
keypoint_positions[keypoint_name] = pos
|
| 238 |
+
|
| 239 |
+
# Create sphere markers for keypoints
|
| 240 |
+
for keypoint_name, pos in keypoint_positions.items():
|
| 241 |
+
marker_scale = 0.1 if keypoint_name in self.large_keypoints else 0.05
|
| 242 |
+
|
| 243 |
+
marker = Marker()
|
| 244 |
+
marker.header.frame_id = "map"
|
| 245 |
+
marker.header.stamp = self.get_clock().now().to_msg()
|
| 246 |
+
marker.ns = f"keypoints_{person_id}"
|
| 247 |
+
marker.id = marker_id_counter
|
| 248 |
+
marker.type = Marker.SPHERE
|
| 249 |
+
marker.action = Marker.ADD
|
| 250 |
+
marker.lifetime = self.timeout.to_msg()
|
| 251 |
+
|
| 252 |
+
marker.pose.position.x, marker.pose.position.y, marker.pose.position.z = pos
|
| 253 |
+
marker.pose.orientation.w = 1.0
|
| 254 |
+
|
| 255 |
+
marker.scale.x = marker.scale.y = marker.scale.z = marker_scale
|
| 256 |
+
marker.color.r, marker.color.g, marker.color.b = color
|
| 257 |
+
marker.color.a = 1.0
|
| 258 |
+
|
| 259 |
+
markers.append(marker)
|
| 260 |
+
marker_id_counter += 1
|
| 261 |
+
|
| 262 |
+
# Create line markers for bones
|
| 263 |
+
if keypoint_positions:
|
| 264 |
+
line_marker = Marker()
|
| 265 |
+
line_marker.header.frame_id = "map"
|
| 266 |
+
line_marker.header.stamp = self.get_clock().now().to_msg()
|
| 267 |
+
line_marker.ns = f"bones_{person_id}"
|
| 268 |
+
line_marker.id = 0
|
| 269 |
+
line_marker.type = Marker.LINE_LIST
|
| 270 |
+
line_marker.action = Marker.ADD
|
| 271 |
+
line_marker.lifetime = self.timeout.to_msg()
|
| 272 |
+
|
| 273 |
+
for joint1, joint2 in self.skeleton_connections:
|
| 274 |
+
if joint1 in keypoint_positions and joint2 in keypoint_positions:
|
| 275 |
+
p1_tuple, p2_tuple = keypoint_positions[joint1], keypoint_positions[joint2]
|
| 276 |
+
|
| 277 |
+
p1, p2 = Point(), Point()
|
| 278 |
+
p1.x, p1.y, p1.z = p1_tuple
|
| 279 |
+
p2.x, p2.y, p2.z = p2_tuple
|
| 280 |
+
line_marker.points.append(p1)
|
| 281 |
+
line_marker.points.append(p2)
|
| 282 |
+
|
| 283 |
+
line_marker.scale.x = 0.02
|
| 284 |
+
line_marker.color.r, line_marker.color.g, line_marker.color.b = color
|
| 285 |
+
line_marker.color.a = 0.8
|
| 286 |
+
|
| 287 |
+
if line_marker.points:
|
| 288 |
+
markers.append(line_marker)
|
| 289 |
+
|
| 290 |
+
# Create text label for person ID
|
| 291 |
+
if 'neck' in keypoint_positions:
|
| 292 |
+
neck_pos = keypoint_positions['neck']
|
| 293 |
+
|
| 294 |
+
text_marker = Marker()
|
| 295 |
+
text_marker.header.frame_id = "map"
|
| 296 |
+
text_marker.header.stamp = self.get_clock().now().to_msg()
|
| 297 |
+
text_marker.ns = f"labels_{person_id}"
|
| 298 |
+
text_marker.id = 0
|
| 299 |
+
text_marker.type = Marker.TEXT_VIEW_FACING
|
| 300 |
+
text_marker.action = Marker.ADD
|
| 301 |
+
text_marker.lifetime = self.timeout.to_msg()
|
| 302 |
+
|
| 303 |
+
text_marker.pose.position.x = neck_pos[0]
|
| 304 |
+
text_marker.pose.position.y = neck_pos[1]
|
| 305 |
+
text_marker.pose.position.z = neck_pos[2] + 0.5 # Display slightly above the neck
|
| 306 |
+
|
| 307 |
+
text_marker.text = f"ID: {person_id}"
|
| 308 |
+
text_marker.scale.z = 0.15 # Text height
|
| 309 |
+
|
| 310 |
+
text_marker.color.r = 1.0
|
| 311 |
+
text_marker.color.g = 1.0
|
| 312 |
+
text_marker.color.b = 1.0
|
| 313 |
+
text_marker.color.a = 1.0
|
| 314 |
+
|
| 315 |
+
markers.append(text_marker)
|
| 316 |
+
|
| 317 |
+
return markers
|
| 318 |
+
|
| 319 |
+
def _init_multi_chunk_mode(self, index_file_path):
|
| 320 |
+
"""Initialize multi-chunk playback mode from index file"""
|
| 321 |
+
try:
|
| 322 |
+
index_df = pd.read_csv(index_file_path)
|
| 323 |
+
self.get_logger().info(f'Loaded index file: {index_file_path}')
|
| 324 |
+
self.get_logger().info(f'Found {len(index_df)} chunks')
|
| 325 |
+
|
| 326 |
+
# Validate required columns
|
| 327 |
+
required_cols = ['chunk_key', 'chunk_start_timestamp', 'chunk_end_timestamp']
|
| 328 |
+
missing_cols = [col for col in required_cols if col not in index_df.columns]
|
| 329 |
+
if missing_cols:
|
| 330 |
+
self.get_logger().error(f'Missing required columns in index: {missing_cols}')
|
| 331 |
+
return
|
| 332 |
+
|
| 333 |
+
# Parse timestamps and sort by start time
|
| 334 |
+
index_df['chunk_start_timestamp'] = pd.to_datetime(index_df['chunk_start_timestamp'])
|
| 335 |
+
index_df['chunk_end_timestamp'] = pd.to_datetime(index_df['chunk_end_timestamp'])
|
| 336 |
+
index_df = index_df.sort_values('chunk_start_timestamp').reset_index(drop=True)
|
| 337 |
+
|
| 338 |
+
# Get base directory from index file path
|
| 339 |
+
base_dir = Path(index_file_path).parent
|
| 340 |
+
|
| 341 |
+
# Store chunk information
|
| 342 |
+
for _, row in index_df.iterrows():
|
| 343 |
+
chunk_key = row['chunk_key']
|
| 344 |
+
filename = f"chunk_{chunk_key}"
|
| 345 |
+
chunk_path = base_dir / f"{filename}.csv"
|
| 346 |
+
self.chunks.append({
|
| 347 |
+
'path': str(chunk_path),
|
| 348 |
+
'key': chunk_key,
|
| 349 |
+
'filename': filename,
|
| 350 |
+
'start': row['chunk_start_timestamp'],
|
| 351 |
+
'end': row['chunk_end_timestamp']
|
| 352 |
+
})
|
| 353 |
+
|
| 354 |
+
self.get_logger().info(f'Chunk playback order:')
|
| 355 |
+
for i, chunk in enumerate(self.chunks):
|
| 356 |
+
self.get_logger().info(f' {i+1}. {chunk["filename"]}.csv')
|
| 357 |
+
|
| 358 |
+
# Load first chunk
|
| 359 |
+
if not self._load_chunk(0):
|
| 360 |
+
self.get_logger().error('Failed to load first chunk')
|
| 361 |
+
return
|
| 362 |
+
|
| 363 |
+
except Exception as e:
|
| 364 |
+
self.get_logger().error(f'Failed to initialize multi-chunk mode: {e}')
|
| 365 |
+
import traceback
|
| 366 |
+
self.get_logger().error(traceback.format_exc())
|
| 367 |
+
|
| 368 |
+
def _init_single_chunk_mode(self, csv_file_path):
|
| 369 |
+
"""Initialize single chunk playback mode (original behavior)"""
|
| 370 |
+
self.get_logger().info('Single chunk mode')
|
| 371 |
+
self._load_csv_data(csv_file_path)
|
| 372 |
+
|
| 373 |
+
def _load_chunk(self, chunk_idx):
|
| 374 |
+
"""Load a specific chunk by index"""
|
| 375 |
+
if chunk_idx >= len(self.chunks):
|
| 376 |
+
return False
|
| 377 |
+
|
| 378 |
+
chunk = self.chunks[chunk_idx]
|
| 379 |
+
self.get_logger().info(f'Loading chunk {chunk_idx + 1}/{len(self.chunks)}: {chunk["filename"]}')
|
| 380 |
+
|
| 381 |
+
if self._load_csv_data(chunk['path']):
|
| 382 |
+
self.current_chunk_idx = chunk_idx
|
| 383 |
+
return True
|
| 384 |
+
return False
|
| 385 |
+
|
| 386 |
+
def _preload_next_chunk(self):
|
| 387 |
+
"""Preload the next chunk in background"""
|
| 388 |
+
next_idx = self.current_chunk_idx + 1
|
| 389 |
+
if next_idx >= len(self.chunks) or self.next_chunk_df is not None:
|
| 390 |
+
return
|
| 391 |
+
|
| 392 |
+
chunk = self.chunks[next_idx]
|
| 393 |
+
self.get_logger().info(f'Preloading next chunk: {chunk["filename"]}')
|
| 394 |
+
|
| 395 |
+
try:
|
| 396 |
+
df = pd.read_csv(chunk['path'])
|
| 397 |
+
|
| 398 |
+
# Process timestamps
|
| 399 |
+
if not pd.api.types.is_datetime64_any_dtype(df['timestamp']):
|
| 400 |
+
try:
|
| 401 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'], format='ISO8601')
|
| 402 |
+
except:
|
| 403 |
+
try:
|
| 404 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'], format='mixed')
|
| 405 |
+
except:
|
| 406 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'])
|
| 407 |
+
|
| 408 |
+
# Convert to seconds from start
|
| 409 |
+
df['time_seconds'] = (df['timestamp'] - df['timestamp'].min()).dt.total_seconds()
|
| 410 |
+
df = df.sort_values('time_seconds').reset_index(drop=True)
|
| 411 |
+
|
| 412 |
+
self.next_chunk_df = df
|
| 413 |
+
self.get_logger().info(f'Preloaded chunk {chunk["filename"]}: {len(df)} rows')
|
| 414 |
+
|
| 415 |
+
except Exception as e:
|
| 416 |
+
self.get_logger().error(f'Failed to preload chunk {chunk["filename"]}: {e}')
|
| 417 |
+
|
| 418 |
+
def _switch_to_next_chunk(self):
|
| 419 |
+
"""Switch to the preloaded next chunk"""
|
| 420 |
+
if self.next_chunk_df is None:
|
| 421 |
+
if self.current_chunk_idx + 1 < len(self.chunks):
|
| 422 |
+
if not self._load_chunk(self.current_chunk_idx + 1):
|
| 423 |
+
self.get_logger().warn('No more chunks to play')
|
| 424 |
+
return False
|
| 425 |
+
else:
|
| 426 |
+
self.get_logger().info('All chunks played. Looping to first chunk...')
|
| 427 |
+
self._load_chunk(0)
|
| 428 |
+
return True
|
| 429 |
+
else:
|
| 430 |
+
self.df = self.next_chunk_df
|
| 431 |
+
self.next_chunk_df = None
|
| 432 |
+
self.current_chunk_idx += 1
|
| 433 |
+
|
| 434 |
+
self.start_time = float(self.df['time_seconds'].min())
|
| 435 |
+
self.end_time = float(self.df['time_seconds'].max())
|
| 436 |
+
self.current_time = self.start_time
|
| 437 |
+
self.previous_persons = set()
|
| 438 |
+
|
| 439 |
+
chunk = self.chunks[self.current_chunk_idx]
|
| 440 |
+
self.get_logger().info(f'Switched to chunk {self.current_chunk_idx + 1}/{len(self.chunks)}: {chunk["filename"]}')
|
| 441 |
+
self.get_logger().info(f'Duration: {self.end_time - self.start_time:.2f} seconds')
|
| 442 |
+
|
| 443 |
+
return True
|
| 444 |
+
|
| 445 |
+
def _load_csv_data(self, csv_file_path):
|
| 446 |
+
"""Load CSV data from file"""
|
| 447 |
+
try:
|
| 448 |
+
df = pd.read_csv(csv_file_path)
|
| 449 |
+
self.get_logger().info(f'Successfully loaded: {Path(csv_file_path).name} ({len(df)} rows)')
|
| 450 |
+
|
| 451 |
+
# Validate required columns
|
| 452 |
+
required_cols = ['timestamp', 'person_track_id']
|
| 453 |
+
missing_cols = [col for col in required_cols if col not in df.columns]
|
| 454 |
+
if missing_cols:
|
| 455 |
+
self.get_logger().error(f'Missing required columns: {missing_cols}')
|
| 456 |
+
return False
|
| 457 |
+
|
| 458 |
+
# Convert timestamp to datetime
|
| 459 |
+
if not pd.api.types.is_datetime64_any_dtype(df['timestamp']):
|
| 460 |
+
self.get_logger().info('Converting timestamp to datetime...')
|
| 461 |
+
try:
|
| 462 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'], format='ISO8601')
|
| 463 |
+
except:
|
| 464 |
+
try:
|
| 465 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'], format='mixed')
|
| 466 |
+
except:
|
| 467 |
+
df['timestamp'] = pd.to_datetime(df['timestamp'])
|
| 468 |
+
|
| 469 |
+
self.get_logger().info('Successfully parsed timestamps')
|
| 470 |
+
|
| 471 |
+
# Convert to seconds from start
|
| 472 |
+
df['time_seconds'] = (df['timestamp'] - df['timestamp'].min()).dt.total_seconds()
|
| 473 |
+
|
| 474 |
+
# Sort by time
|
| 475 |
+
df = df.sort_values('time_seconds').reset_index(drop=True)
|
| 476 |
+
|
| 477 |
+
# Store data
|
| 478 |
+
self.df = df
|
| 479 |
+
self.start_time = float(df['time_seconds'].min())
|
| 480 |
+
self.end_time = float(df['time_seconds'].max())
|
| 481 |
+
self.current_time = self.start_time
|
| 482 |
+
|
| 483 |
+
self.get_logger().info(f'Time range: {self.start_time:.2f} to {self.end_time:.2f} seconds')
|
| 484 |
+
self.get_logger().info(f'Duration: {self.end_time - self.start_time:.2f} seconds')
|
| 485 |
+
self.get_logger().info(f'Unique persons: {df["person_track_id"].nunique()}')
|
| 486 |
+
|
| 487 |
+
return True
|
| 488 |
+
|
| 489 |
+
except FileNotFoundError:
|
| 490 |
+
self.get_logger().error(f'CSV file not found: {csv_file_path}')
|
| 491 |
+
return False
|
| 492 |
+
except Exception as e:
|
| 493 |
+
self.get_logger().error(f'Failed to load CSV file: {e}')
|
| 494 |
+
import traceback
|
| 495 |
+
self.get_logger().error(traceback.format_exc())
|
| 496 |
+
return False
|
| 497 |
+
|
| 498 |
+
def publish_callback(self):
|
| 499 |
+
if self.df is None:
|
| 500 |
+
return
|
| 501 |
+
|
| 502 |
+
# Check if we need to preload next chunk
|
| 503 |
+
if self.chunks and self.next_chunk_df is None:
|
| 504 |
+
time_remaining = self.end_time - self.current_time
|
| 505 |
+
if time_remaining <= self.preload_threshold:
|
| 506 |
+
self._preload_next_chunk()
|
| 507 |
+
|
| 508 |
+
# Use the EXACT same timestamp for all tracks in this update cycle
|
| 509 |
+
publish_timestamp = float(self.current_time)
|
| 510 |
+
|
| 511 |
+
# Get all unique persons that exist in a window around current time
|
| 512 |
+
time_window = 0.5 # Look ahead/behind 0.5 seconds to find all active persons
|
| 513 |
+
nearby_data = self.df[
|
| 514 |
+
(self.df['time_seconds'] >= self.current_time - time_window) &
|
| 515 |
+
(self.df['time_seconds'] <= self.current_time + time_window)
|
| 516 |
+
]
|
| 517 |
+
|
| 518 |
+
current_persons = set()
|
| 519 |
+
marker_array = MarkerArray()
|
| 520 |
+
|
| 521 |
+
if not nearby_data.empty:
|
| 522 |
+
# Get all unique persons in this time window
|
| 523 |
+
unique_persons = nearby_data['person_track_id'].unique()
|
| 524 |
+
|
| 525 |
+
# For each person, get frame and create markers
|
| 526 |
+
for person_id in unique_persons:
|
| 527 |
+
person_id_str = str(person_id)
|
| 528 |
+
current_persons.add(person_id_str)
|
| 529 |
+
|
| 530 |
+
# Get frame for person (interpolated or nearest based on settings)
|
| 531 |
+
frame = self._get_frame_for_person(person_id, self.current_time)
|
| 532 |
+
|
| 533 |
+
if frame is not None:
|
| 534 |
+
# Create all markers for this person
|
| 535 |
+
person_markers = self._create_markers_for_person(
|
| 536 |
+
person_id_str,
|
| 537 |
+
frame,
|
| 538 |
+
publish_timestamp
|
| 539 |
+
)
|
| 540 |
+
marker_array.markers.extend(person_markers)
|
| 541 |
+
|
| 542 |
+
mode_str = "interpolated" if self.interpolate else "nearest"
|
| 543 |
+
self.get_logger().debug(f'Created {mode_str} markers for {len(unique_persons)} persons at t={publish_timestamp:.2f}s')
|
| 544 |
+
|
| 545 |
+
# Create deletion markers for persons that left
|
| 546 |
+
persons_left = self.previous_persons - current_persons
|
| 547 |
+
for person_id in persons_left:
|
| 548 |
+
self.get_logger().info(f'Person {person_id} left the scene')
|
| 549 |
+
|
| 550 |
+
# Delete keypoints
|
| 551 |
+
delete_marker = Marker()
|
| 552 |
+
delete_marker.action = Marker.DELETEALL
|
| 553 |
+
delete_marker.ns = f"keypoints_{person_id}"
|
| 554 |
+
marker_array.markers.append(delete_marker)
|
| 555 |
+
|
| 556 |
+
# Delete bones
|
| 557 |
+
delete_marker_bones = Marker()
|
| 558 |
+
delete_marker_bones.action = Marker.DELETEALL
|
| 559 |
+
delete_marker_bones.ns = f"bones_{person_id}"
|
| 560 |
+
marker_array.markers.append(delete_marker_bones)
|
| 561 |
+
|
| 562 |
+
# Delete labels
|
| 563 |
+
delete_marker_labels = Marker()
|
| 564 |
+
delete_marker_labels.action = Marker.DELETEALL
|
| 565 |
+
delete_marker_labels.ns = f"labels_{person_id}"
|
| 566 |
+
marker_array.markers.append(delete_marker_labels)
|
| 567 |
+
|
| 568 |
+
# Publish all markers at once
|
| 569 |
+
if marker_array.markers:
|
| 570 |
+
self.marker_pub.publish(marker_array)
|
| 571 |
+
|
| 572 |
+
# Update previous persons
|
| 573 |
+
self.previous_persons = current_persons
|
| 574 |
+
|
| 575 |
+
# Advance time
|
| 576 |
+
time_step = (1.0 / self.update_rate) * self.playback_speed
|
| 577 |
+
self.current_time += time_step
|
| 578 |
+
|
| 579 |
+
# Check if we've reached the end
|
| 580 |
+
if self.current_time > self.end_time:
|
| 581 |
+
if self.chunks:
|
| 582 |
+
if not self._switch_to_next_chunk():
|
| 583 |
+
self.get_logger().info('Playback finished.')
|
| 584 |
+
else:
|
| 585 |
+
self.get_logger().info('Playback finished. Looping...')
|
| 586 |
+
self.current_time = self.start_time
|
| 587 |
+
self.previous_persons = set()
|
| 588 |
+
|
| 589 |
+
|
| 590 |
+
def main(args=None):
|
| 591 |
+
parser = argparse.ArgumentParser(
|
| 592 |
+
description='Publish skeleton keypoint visualization markers from CSV file(s)')
|
| 593 |
+
parser.add_argument('csv_file', type=str, nargs='?',
|
| 594 |
+
help='Path to a single CSV file with keypoint data')
|
| 595 |
+
parser.add_argument('--index', type=str,
|
| 596 |
+
help='Path to index CSV file for multi-chunk playback')
|
| 597 |
+
parser.add_argument('--speed', type=float, default=1.0,
|
| 598 |
+
help='Playback speed multiplier (default: 1.0)')
|
| 599 |
+
parser.add_argument('--rate', type=float, default=30.0,
|
| 600 |
+
help='Publishing rate in Hz (default: 10.0)')
|
| 601 |
+
parser.add_argument('--interpolate', action='store_true',
|
| 602 |
+
help='Enable linear interpolation between frames (default: disabled)')
|
| 603 |
+
|
| 604 |
+
import sys
|
| 605 |
+
filtered_args = [arg for arg in sys.argv[1:] if not arg.startswith('__')]
|
| 606 |
+
parsed_args, unknown = parser.parse_known_args(filtered_args)
|
| 607 |
+
|
| 608 |
+
if not parsed_args.csv_file and not parsed_args.index:
|
| 609 |
+
parser.error('Either csv_file or --index must be provided')
|
| 610 |
+
|
| 611 |
+
rclpy.init(args=args)
|
| 612 |
+
node = KeypointPublisher(
|
| 613 |
+
csv_file_path=parsed_args.csv_file,
|
| 614 |
+
index_file_path=parsed_args.index,
|
| 615 |
+
playback_speed=parsed_args.speed,
|
| 616 |
+
publish_rate=parsed_args.rate,
|
| 617 |
+
interpolate=parsed_args.interpolate
|
| 618 |
+
)
|
| 619 |
+
|
| 620 |
+
try:
|
| 621 |
+
rclpy.spin(node)
|
| 622 |
+
except KeyboardInterrupt:
|
| 623 |
+
pass
|
| 624 |
+
finally:
|
| 625 |
+
node.destroy_node()
|
| 626 |
+
rclpy.shutdown()
|
| 627 |
+
|
| 628 |
+
|
| 629 |
+
if __name__ == '__main__':
|
| 630 |
+
main()
|
keypoint-db/ws/src/db_loader/db_loader/layout_publisher.py
ADDED
|
@@ -0,0 +1,91 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
|
| 3 |
+
import rclpy
|
| 4 |
+
from rclpy.node import Node
|
| 5 |
+
from std_msgs.msg import String
|
| 6 |
+
import json
|
| 7 |
+
import argparse
|
| 8 |
+
|
| 9 |
+
|
| 10 |
+
class LayoutPublisher(Node):
|
| 11 |
+
def __init__(self, json_file_path, rate=None):
|
| 12 |
+
super().__init__('layout_publisher')
|
| 13 |
+
self.publisher = self.create_publisher(String, 'layout_data', 10)
|
| 14 |
+
self.continuous = rate is not None
|
| 15 |
+
|
| 16 |
+
# Read the JSON file
|
| 17 |
+
try:
|
| 18 |
+
with open(json_file_path, 'r') as f:
|
| 19 |
+
self.layout_data = json.load(f)
|
| 20 |
+
self.get_logger().info(f'Successfully loaded layout JSON file: {json_file_path}')
|
| 21 |
+
|
| 22 |
+
if self.continuous:
|
| 23 |
+
# Publish continuously at specified rate
|
| 24 |
+
self.get_logger().info(f'Publishing continuously at {rate} Hz')
|
| 25 |
+
self.timer = self.create_timer(1.0 / rate, self.publish_layout)
|
| 26 |
+
else:
|
| 27 |
+
# Publish once after a short delay
|
| 28 |
+
self.get_logger().info('Publishing once')
|
| 29 |
+
self.timer = self.create_timer(0.5, self.publish_once)
|
| 30 |
+
|
| 31 |
+
except FileNotFoundError:
|
| 32 |
+
self.get_logger().error(f'JSON file not found: {json_file_path}')
|
| 33 |
+
self.layout_data = None
|
| 34 |
+
except json.JSONDecodeError as e:
|
| 35 |
+
self.get_logger().error(f'Failed to parse JSON: {e}')
|
| 36 |
+
self.layout_data = None
|
| 37 |
+
|
| 38 |
+
def publish_layout(self):
|
| 39 |
+
"""Publish continuously"""
|
| 40 |
+
if self.layout_data is None:
|
| 41 |
+
self.get_logger().warn('No layout data to publish')
|
| 42 |
+
return
|
| 43 |
+
|
| 44 |
+
msg = String()
|
| 45 |
+
msg.data = json.dumps(self.layout_data)
|
| 46 |
+
self.publisher.publish(msg)
|
| 47 |
+
self.get_logger().info(f'Published layout data for: {self.layout_data.get("name", "Unknown")}')
|
| 48 |
+
|
| 49 |
+
def publish_once(self):
|
| 50 |
+
"""Publish once and shutdown"""
|
| 51 |
+
if self.layout_data is None:
|
| 52 |
+
self.get_logger().error('No layout data to publish')
|
| 53 |
+
rclpy.shutdown()
|
| 54 |
+
return
|
| 55 |
+
|
| 56 |
+
msg = String()
|
| 57 |
+
msg.data = json.dumps(self.layout_data)
|
| 58 |
+
self.publisher.publish(msg)
|
| 59 |
+
self.get_logger().info(f'Published layout data for: {self.layout_data.get("name", "Unknown")}')
|
| 60 |
+
|
| 61 |
+
# Cancel timer and shutdown
|
| 62 |
+
self.timer.cancel()
|
| 63 |
+
rclpy.shutdown()
|
| 64 |
+
|
| 65 |
+
|
| 66 |
+
def main(args=None):
|
| 67 |
+
parser = argparse.ArgumentParser(description='Publish layout JSON data to ROS 2 topic')
|
| 68 |
+
parser.add_argument('json_file', type=str, help='Path to the JSON layout file')
|
| 69 |
+
parser.add_argument('--rate', type=float, default=None,
|
| 70 |
+
help='Publishing rate in Hz. If not specified, publishes once and exits')
|
| 71 |
+
|
| 72 |
+
import sys
|
| 73 |
+
filtered_args = [arg for arg in sys.argv[1:] if not arg.startswith('__')]
|
| 74 |
+
|
| 75 |
+
# Use parse_known_args instead of parse_args to ignore ROS arguments
|
| 76 |
+
parsed_args, unknown = parser.parse_known_args(filtered_args)
|
| 77 |
+
|
| 78 |
+
rclpy.init(args=args)
|
| 79 |
+
node = LayoutPublisher(parsed_args.json_file, parsed_args.rate)
|
| 80 |
+
|
| 81 |
+
try:
|
| 82 |
+
rclpy.spin(node)
|
| 83 |
+
except KeyboardInterrupt:
|
| 84 |
+
pass
|
| 85 |
+
finally:
|
| 86 |
+
node.destroy_node()
|
| 87 |
+
rclpy.shutdown()
|
| 88 |
+
|
| 89 |
+
|
| 90 |
+
if __name__ == '__main__':
|
| 91 |
+
main()
|
keypoint-db/ws/src/db_loader/db_loader/layout_visualizer.py
ADDED
|
@@ -0,0 +1,407 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
|
| 3 |
+
import rclpy
|
| 4 |
+
from rclpy.node import Node
|
| 5 |
+
from std_msgs.msg import String
|
| 6 |
+
from visualization_msgs.msg import Marker, MarkerArray
|
| 7 |
+
from geometry_msgs.msg import Point
|
| 8 |
+
import json
|
| 9 |
+
import numpy as np
|
| 10 |
+
|
| 11 |
+
|
| 12 |
+
class LayoutVisualizer(Node):
|
| 13 |
+
def __init__(self, use_filled_shelves=False, shelf_alpha=0.3):
|
| 14 |
+
super().__init__('layout_visualizer')
|
| 15 |
+
|
| 16 |
+
self.use_filled_shelves = use_filled_shelves
|
| 17 |
+
self.shelf_alpha = shelf_alpha
|
| 18 |
+
|
| 19 |
+
self.subscription = self.create_subscription(
|
| 20 |
+
String,
|
| 21 |
+
'layout_data',
|
| 22 |
+
self.layout_callback,
|
| 23 |
+
10
|
| 24 |
+
)
|
| 25 |
+
|
| 26 |
+
self.marker_pub = self.create_publisher(
|
| 27 |
+
MarkerArray,
|
| 28 |
+
'layout_markers',
|
| 29 |
+
10
|
| 30 |
+
)
|
| 31 |
+
|
| 32 |
+
self.get_logger().info(f'Layout visualizer started! Filled shelves: {use_filled_shelves}, Alpha: {shelf_alpha}')
|
| 33 |
+
|
| 34 |
+
def layout_callback(self, msg):
|
| 35 |
+
try:
|
| 36 |
+
layout = json.loads(msg.data)
|
| 37 |
+
self.get_logger().info(f'Received layout: {layout.get("name", "Unknown")}')
|
| 38 |
+
|
| 39 |
+
# Create marker array
|
| 40 |
+
marker_array = MarkerArray()
|
| 41 |
+
marker_id = 0
|
| 42 |
+
|
| 43 |
+
# Visualize perimeters
|
| 44 |
+
if 'perimeters' in layout:
|
| 45 |
+
for perimeter in layout['perimeters']:
|
| 46 |
+
marker = self.create_perimeter_marker(perimeter, marker_id)
|
| 47 |
+
marker_array.markers.append(marker)
|
| 48 |
+
marker_id += 1
|
| 49 |
+
|
| 50 |
+
# Visualize exits
|
| 51 |
+
if 'exits' in layout:
|
| 52 |
+
for exit_data in layout['exits']:
|
| 53 |
+
marker = self.create_exit_marker(exit_data, marker_id)
|
| 54 |
+
marker_array.markers.append(marker)
|
| 55 |
+
marker_id += 1
|
| 56 |
+
|
| 57 |
+
# Visualize shelves
|
| 58 |
+
if 'shelves' in layout:
|
| 59 |
+
for shelf in layout['shelves']:
|
| 60 |
+
# Pass marker_id and get back the updated marker_id
|
| 61 |
+
markers, marker_id = self.create_shelf_markers(shelf, marker_id)
|
| 62 |
+
marker_array.markers.extend(markers)
|
| 63 |
+
|
| 64 |
+
# Publish markers
|
| 65 |
+
self.marker_pub.publish(marker_array)
|
| 66 |
+
self.get_logger().info(f'Published {len(marker_array.markers)} markers')
|
| 67 |
+
|
| 68 |
+
except json.JSONDecodeError as e:
|
| 69 |
+
self.get_logger().error(f'Failed to parse JSON: {e}')
|
| 70 |
+
except Exception as e:
|
| 71 |
+
self.get_logger().error(f'An unexpected error occurred in layout_callback: {e}')
|
| 72 |
+
import traceback
|
| 73 |
+
self.get_logger().error(traceback.format_exc())
|
| 74 |
+
|
| 75 |
+
def create_perimeter_marker(self, perimeter, marker_id):
|
| 76 |
+
marker = Marker()
|
| 77 |
+
marker.header.frame_id = "map"
|
| 78 |
+
marker.header.stamp = self.get_clock().now().to_msg()
|
| 79 |
+
marker.ns = "perimeters"
|
| 80 |
+
marker.id = marker_id
|
| 81 |
+
marker.type = Marker.LINE_STRIP
|
| 82 |
+
marker.action = Marker.ADD
|
| 83 |
+
marker.lifetime = rclpy.duration.Duration(seconds=0).to_msg()
|
| 84 |
+
|
| 85 |
+
# Set color based on perimeter type
|
| 86 |
+
perimeter_type = perimeter.get('perimeter_type', '')
|
| 87 |
+
if perimeter_type == 'tracking_area':
|
| 88 |
+
marker.color.r = 0.0
|
| 89 |
+
marker.color.g = 0.0
|
| 90 |
+
marker.color.b = 0.0
|
| 91 |
+
marker.color.a = 1.0
|
| 92 |
+
marker.scale.x = 0.05
|
| 93 |
+
elif perimeter_type == 'payment_area':
|
| 94 |
+
marker.color.r = 1.0
|
| 95 |
+
marker.color.g = 0.0
|
| 96 |
+
marker.color.b = 0.0
|
| 97 |
+
marker.color.a = 0.5
|
| 98 |
+
marker.scale.x = 0.03
|
| 99 |
+
elif perimeter_type == 'employee_area':
|
| 100 |
+
marker.color.r = 1.0
|
| 101 |
+
marker.color.g = 1.0
|
| 102 |
+
marker.color.b = 0.0
|
| 103 |
+
marker.color.a = 0.5
|
| 104 |
+
marker.scale.x = 0.03
|
| 105 |
+
else:
|
| 106 |
+
marker.color.r = 0.5
|
| 107 |
+
marker.color.g = 0.5
|
| 108 |
+
marker.color.b = 0.5
|
| 109 |
+
marker.color.a = 0.5
|
| 110 |
+
marker.scale.x = 0.02
|
| 111 |
+
|
| 112 |
+
# Add points
|
| 113 |
+
for coord in perimeter['geometry']:
|
| 114 |
+
p = Point()
|
| 115 |
+
p.x = float(coord[0])
|
| 116 |
+
p.y = float(coord[1])
|
| 117 |
+
p.z = float(coord[2])
|
| 118 |
+
marker.points.append(p)
|
| 119 |
+
|
| 120 |
+
# Close the loop
|
| 121 |
+
if marker.points:
|
| 122 |
+
marker.points.append(marker.points[0])
|
| 123 |
+
|
| 124 |
+
return marker
|
| 125 |
+
|
| 126 |
+
def create_exit_marker(self, exit_data, marker_id):
|
| 127 |
+
marker = Marker()
|
| 128 |
+
marker.header.frame_id = "map"
|
| 129 |
+
marker.header.stamp = self.get_clock().now().to_msg()
|
| 130 |
+
marker.ns = "exits"
|
| 131 |
+
marker.id = marker_id
|
| 132 |
+
marker.type = Marker.LINE_STRIP
|
| 133 |
+
marker.action = Marker.ADD
|
| 134 |
+
marker.lifetime = rclpy.duration.Duration(seconds=0).to_msg()
|
| 135 |
+
|
| 136 |
+
# Set color based on exit type
|
| 137 |
+
exit_type = exit_data.get('exit_type', '')
|
| 138 |
+
if exit_type == 'employee_only':
|
| 139 |
+
marker.color.r = 1.0
|
| 140 |
+
marker.color.g = 0.5
|
| 141 |
+
marker.color.b = 0.0
|
| 142 |
+
elif exit_type == 'emergency':
|
| 143 |
+
marker.color.r = 1.0
|
| 144 |
+
marker.color.g = 0.0
|
| 145 |
+
marker.color.b = 0.0
|
| 146 |
+
else:
|
| 147 |
+
marker.color.r = 0.0
|
| 148 |
+
marker.color.g = 1.0
|
| 149 |
+
marker.color.b = 0.0
|
| 150 |
+
|
| 151 |
+
marker.color.a = 0.8
|
| 152 |
+
marker.scale.x = 0.08
|
| 153 |
+
|
| 154 |
+
# Add points
|
| 155 |
+
for coord in exit_data['geometry']:
|
| 156 |
+
p = Point()
|
| 157 |
+
p.x = float(coord[0])
|
| 158 |
+
p.y = float(coord[1])
|
| 159 |
+
p.z = float(coord[2])
|
| 160 |
+
marker.points.append(p)
|
| 161 |
+
|
| 162 |
+
# Close the loop
|
| 163 |
+
if marker.points:
|
| 164 |
+
marker.points.append(marker.points[0])
|
| 165 |
+
|
| 166 |
+
return marker
|
| 167 |
+
|
| 168 |
+
|
| 169 |
+
def create_shelf_markers(self, shelf, start_marker_id):
|
| 170 |
+
"""Create markers for a shelf and return them with the next available marker ID"""
|
| 171 |
+
markers = []
|
| 172 |
+
marker_id = start_marker_id
|
| 173 |
+
|
| 174 |
+
# Color based on shelf type
|
| 175 |
+
shelf_type = shelf.get('type', '')
|
| 176 |
+
if shelf_type == 'shelf':
|
| 177 |
+
r, g, b = 0.0, 0.5, 1.0
|
| 178 |
+
elif shelf_type == 'behind_billing_counter':
|
| 179 |
+
r, g, b = 0.8, 0.2, 0.8
|
| 180 |
+
elif shelf_type == 'non_merchandise':
|
| 181 |
+
r, g, b = 0.5, 0.5, 0.5
|
| 182 |
+
else:
|
| 183 |
+
r, g, b = 0.0, 0.7, 1.0
|
| 184 |
+
|
| 185 |
+
vertices = shelf['shelf_bounds']['vertices']
|
| 186 |
+
|
| 187 |
+
if self.use_filled_shelves:
|
| 188 |
+
# Create filled CUBE marker with proper orientation
|
| 189 |
+
cube_marker = Marker()
|
| 190 |
+
cube_marker.header.frame_id = "map"
|
| 191 |
+
cube_marker.header.stamp = self.get_clock().now().to_msg()
|
| 192 |
+
cube_marker.ns = "shelves_filled"
|
| 193 |
+
cube_marker.id = marker_id
|
| 194 |
+
cube_marker.type = Marker.CUBE
|
| 195 |
+
cube_marker.action = Marker.ADD
|
| 196 |
+
cube_marker.lifetime = rclpy.duration.Duration(seconds=0).to_msg()
|
| 197 |
+
|
| 198 |
+
# Set position (center of the shelf)
|
| 199 |
+
center = shelf['shelf_bounds']['center']
|
| 200 |
+
cube_marker.pose.position.x = float(center[0])
|
| 201 |
+
cube_marker.pose.position.y = float(center[1])
|
| 202 |
+
cube_marker.pose.position.z = float(center[2])
|
| 203 |
+
|
| 204 |
+
# Calculate orientation from shelf normal
|
| 205 |
+
# The shelf normal points outward from the front face
|
| 206 |
+
# Default cube has depth in Y direction, so we align Y with the normal
|
| 207 |
+
normal = np.array(shelf['normal'])
|
| 208 |
+
normal = normal / np.linalg.norm(normal) # Normalize
|
| 209 |
+
|
| 210 |
+
# Default cube orientation has depth (Y axis) pointing in +Y direction
|
| 211 |
+
# We need to find the rotation that aligns +Y with the shelf normal
|
| 212 |
+
default_direction = np.array([0.0, 1.0, 0.0]) # Default cube depth direction (Y)
|
| 213 |
+
|
| 214 |
+
# Calculate rotation axis (cross product)
|
| 215 |
+
rotation_axis = np.cross(default_direction, normal)
|
| 216 |
+
rotation_axis_length = np.linalg.norm(rotation_axis)
|
| 217 |
+
|
| 218 |
+
if rotation_axis_length < 1e-6:
|
| 219 |
+
# Vectors are parallel or anti-parallel
|
| 220 |
+
if np.dot(default_direction, normal) > 0:
|
| 221 |
+
# Same direction, no rotation needed
|
| 222 |
+
cube_marker.pose.orientation.w = 1.0
|
| 223 |
+
cube_marker.pose.orientation.x = 0.0
|
| 224 |
+
cube_marker.pose.orientation.y = 0.0
|
| 225 |
+
cube_marker.pose.orientation.z = 0.0
|
| 226 |
+
else:
|
| 227 |
+
# Opposite direction, rotate 180 degrees around X axis
|
| 228 |
+
cube_marker.pose.orientation.w = 0.0
|
| 229 |
+
cube_marker.pose.orientation.x = 1.0
|
| 230 |
+
cube_marker.pose.orientation.y = 0.0
|
| 231 |
+
cube_marker.pose.orientation.z = 0.0
|
| 232 |
+
else:
|
| 233 |
+
# Normalize rotation axis
|
| 234 |
+
rotation_axis = rotation_axis / rotation_axis_length
|
| 235 |
+
|
| 236 |
+
# Calculate rotation angle
|
| 237 |
+
rotation_angle = np.arccos(np.clip(np.dot(default_direction, normal), -1.0, 1.0))
|
| 238 |
+
|
| 239 |
+
# Convert to quaternion
|
| 240 |
+
half_angle = rotation_angle / 2.0
|
| 241 |
+
sin_half = np.sin(half_angle)
|
| 242 |
+
|
| 243 |
+
cube_marker.pose.orientation.w = float(np.cos(half_angle))
|
| 244 |
+
cube_marker.pose.orientation.x = float(rotation_axis[0] * sin_half)
|
| 245 |
+
cube_marker.pose.orientation.y = float(rotation_axis[1] * sin_half)
|
| 246 |
+
cube_marker.pose.orientation.z = float(rotation_axis[2] * sin_half)
|
| 247 |
+
|
| 248 |
+
# Set size (dimensions of the shelf)
|
| 249 |
+
# X = width (along the shelf), Y = depth (perpendicular to face), Z = height
|
| 250 |
+
extends = shelf['shelf_bounds']['extends']
|
| 251 |
+
cube_marker.scale.x = float(extends[0] * 2) # width
|
| 252 |
+
cube_marker.scale.y = float(extends[1] * 2) # depth (aligned with normal)
|
| 253 |
+
cube_marker.scale.z = float(extends[2] * 2) # height
|
| 254 |
+
|
| 255 |
+
# Set color with transparency
|
| 256 |
+
cube_marker.color.r = r
|
| 257 |
+
cube_marker.color.g = g
|
| 258 |
+
cube_marker.color.b = b
|
| 259 |
+
cube_marker.color.a = self.shelf_alpha
|
| 260 |
+
|
| 261 |
+
markers.append(cube_marker)
|
| 262 |
+
marker_id += 1
|
| 263 |
+
else:
|
| 264 |
+
# Create wireframe LINE_LIST marker
|
| 265 |
+
box_marker = Marker()
|
| 266 |
+
box_marker.header.frame_id = "map"
|
| 267 |
+
box_marker.header.stamp = self.get_clock().now().to_msg()
|
| 268 |
+
box_marker.ns = "shelves_box"
|
| 269 |
+
box_marker.id = marker_id
|
| 270 |
+
box_marker.type = Marker.LINE_LIST
|
| 271 |
+
box_marker.action = Marker.ADD
|
| 272 |
+
box_marker.lifetime = rclpy.duration.Duration(seconds=0).to_msg()
|
| 273 |
+
box_marker.scale.x = 0.04
|
| 274 |
+
box_marker.color.r = r
|
| 275 |
+
box_marker.color.g = g
|
| 276 |
+
box_marker.color.b = b
|
| 277 |
+
box_marker.color.a = 0.7
|
| 278 |
+
|
| 279 |
+
# Helper function to add an edge
|
| 280 |
+
def add_edge(idx1, idx2):
|
| 281 |
+
if idx1 < len(vertices) and idx2 < len(vertices):
|
| 282 |
+
p1 = Point()
|
| 283 |
+
p1.x = float(vertices[idx1][0])
|
| 284 |
+
p1.y = float(vertices[idx1][1])
|
| 285 |
+
p1.z = float(vertices[idx1][2])
|
| 286 |
+
|
| 287 |
+
p2 = Point()
|
| 288 |
+
p2.x = float(vertices[idx2][0])
|
| 289 |
+
p2.y = float(vertices[idx2][1])
|
| 290 |
+
p2.z = float(vertices[idx2][2])
|
| 291 |
+
|
| 292 |
+
box_marker.points.append(p1)
|
| 293 |
+
box_marker.points.append(p2)
|
| 294 |
+
|
| 295 |
+
# Draw all 12 edges of the box
|
| 296 |
+
# Bottom face
|
| 297 |
+
add_edge(0, 1)
|
| 298 |
+
add_edge(1, 2)
|
| 299 |
+
add_edge(2, 3)
|
| 300 |
+
add_edge(3, 0)
|
| 301 |
+
|
| 302 |
+
# Top face
|
| 303 |
+
add_edge(4, 5)
|
| 304 |
+
add_edge(5, 6)
|
| 305 |
+
add_edge(6, 7)
|
| 306 |
+
add_edge(7, 4)
|
| 307 |
+
|
| 308 |
+
# Vertical edges
|
| 309 |
+
add_edge(0, 4)
|
| 310 |
+
add_edge(1, 5)
|
| 311 |
+
add_edge(2, 6)
|
| 312 |
+
add_edge(3, 7)
|
| 313 |
+
|
| 314 |
+
markers.append(box_marker)
|
| 315 |
+
marker_id += 1
|
| 316 |
+
|
| 317 |
+
# Shelf normal (arrow showing front face)
|
| 318 |
+
normal_marker = Marker()
|
| 319 |
+
normal_marker.header.frame_id = "map"
|
| 320 |
+
normal_marker.header.stamp = self.get_clock().now().to_msg()
|
| 321 |
+
normal_marker.ns = "shelf_normals"
|
| 322 |
+
normal_marker.id = marker_id
|
| 323 |
+
normal_marker.type = Marker.ARROW
|
| 324 |
+
normal_marker.action = Marker.ADD
|
| 325 |
+
normal_marker.lifetime = rclpy.duration.Duration(seconds=0).to_msg()
|
| 326 |
+
|
| 327 |
+
center = shelf['shelf_bounds']['center']
|
| 328 |
+
normal = shelf['normal']
|
| 329 |
+
|
| 330 |
+
start = Point()
|
| 331 |
+
start.x = float(center[0])
|
| 332 |
+
start.y = float(center[1])
|
| 333 |
+
start.z = float(center[2])
|
| 334 |
+
|
| 335 |
+
end = Point()
|
| 336 |
+
end.x = float(center[0] + 0.3 * normal[0])
|
| 337 |
+
end.y = float(center[1] + 0.3 * normal[1])
|
| 338 |
+
end.z = float(center[2] + 0.3 * normal[2])
|
| 339 |
+
|
| 340 |
+
normal_marker.points = [start, end]
|
| 341 |
+
normal_marker.scale.x = 0.03
|
| 342 |
+
normal_marker.scale.y = 0.06
|
| 343 |
+
normal_marker.scale.z = 0.08
|
| 344 |
+
|
| 345 |
+
normal_marker.color.r = 0.0
|
| 346 |
+
normal_marker.color.g = 0.0
|
| 347 |
+
normal_marker.color.b = 1.0
|
| 348 |
+
normal_marker.color.a = 0.8
|
| 349 |
+
|
| 350 |
+
markers.append(normal_marker)
|
| 351 |
+
marker_id += 1
|
| 352 |
+
|
| 353 |
+
# Shelf ID text
|
| 354 |
+
text_marker = Marker()
|
| 355 |
+
text_marker.header.frame_id = "map"
|
| 356 |
+
text_marker.header.stamp = self.get_clock().now().to_msg()
|
| 357 |
+
text_marker.ns = "shelf_labels"
|
| 358 |
+
text_marker.id = marker_id
|
| 359 |
+
text_marker.type = Marker.TEXT_VIEW_FACING
|
| 360 |
+
text_marker.action = Marker.ADD
|
| 361 |
+
text_marker.lifetime = rclpy.duration.Duration(seconds=0).to_msg()
|
| 362 |
+
|
| 363 |
+
text_marker.pose.position.x = float(center[0])
|
| 364 |
+
text_marker.pose.position.y = float(center[1])
|
| 365 |
+
text_marker.pose.position.z = float(center[2]) + 0.3
|
| 366 |
+
|
| 367 |
+
text_marker.text = str(shelf['shelf_id'])
|
| 368 |
+
text_marker.scale.z = 0.3
|
| 369 |
+
|
| 370 |
+
text_marker.color.r = 1.0
|
| 371 |
+
text_marker.color.g = 1.0
|
| 372 |
+
text_marker.color.b = 1.0
|
| 373 |
+
text_marker.color.a = 1.0
|
| 374 |
+
|
| 375 |
+
markers.append(text_marker)
|
| 376 |
+
marker_id += 1
|
| 377 |
+
|
| 378 |
+
return markers, marker_id
|
| 379 |
+
|
| 380 |
+
|
| 381 |
+
def main(args=None):
|
| 382 |
+
import argparse
|
| 383 |
+
import sys
|
| 384 |
+
|
| 385 |
+
parser = argparse.ArgumentParser(description='Visualize layout data')
|
| 386 |
+
parser.add_argument('--filled', action='store_true',
|
| 387 |
+
help='Display shelves as filled transparent boxes')
|
| 388 |
+
parser.add_argument('--alpha', type=float, default=0.3,
|
| 389 |
+
help='Transparency level for filled shelves (0.0-1.0, default: 0.3)')
|
| 390 |
+
|
| 391 |
+
filtered_args = [arg for arg in sys.argv[1:] if not arg.startswith('__')]
|
| 392 |
+
parsed_args, unknown = parser.parse_known_args(filtered_args)
|
| 393 |
+
|
| 394 |
+
rclpy.init(args=args)
|
| 395 |
+
node = LayoutVisualizer(use_filled_shelves=parsed_args.filled, shelf_alpha=parsed_args.alpha)
|
| 396 |
+
|
| 397 |
+
try:
|
| 398 |
+
rclpy.spin(node)
|
| 399 |
+
except KeyboardInterrupt:
|
| 400 |
+
pass
|
| 401 |
+
finally:
|
| 402 |
+
node.destroy_node()
|
| 403 |
+
rclpy.shutdown()
|
| 404 |
+
|
| 405 |
+
|
| 406 |
+
if __name__ == '__main__':
|
| 407 |
+
main()
|
keypoint-db/ws/src/db_loader/launch/layout_visualization_launch.py
ADDED
|
@@ -0,0 +1,127 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
|
| 3 |
+
from launch import LaunchDescription
|
| 4 |
+
from launch.actions import DeclareLaunchArgument, TimerAction
|
| 5 |
+
from launch.conditions import IfCondition
|
| 6 |
+
from launch.substitutions import LaunchConfiguration, PythonExpression
|
| 7 |
+
from launch_ros.actions import Node
|
| 8 |
+
|
| 9 |
+
|
| 10 |
+
def generate_launch_description():
|
| 11 |
+
# Declare launch arguments
|
| 12 |
+
json_file_arg = DeclareLaunchArgument(
|
| 13 |
+
'json_file',
|
| 14 |
+
default_value='',
|
| 15 |
+
description='Path to the JSON layout file'
|
| 16 |
+
)
|
| 17 |
+
|
| 18 |
+
rviz_config_arg = DeclareLaunchArgument(
|
| 19 |
+
'rviz_config',
|
| 20 |
+
default_value='/home/user/ws/src/db_loader/rviz/layout_view.rviz',
|
| 21 |
+
description='Path to RViz config file (leave empty to skip RViz)'
|
| 22 |
+
)
|
| 23 |
+
|
| 24 |
+
publisher_delay_arg = DeclareLaunchArgument(
|
| 25 |
+
'publisher_delay',
|
| 26 |
+
default_value='1.5',
|
| 27 |
+
description='Delay in seconds before starting publishers (to let subscribers connect)'
|
| 28 |
+
)
|
| 29 |
+
|
| 30 |
+
filled_shelves_arg = DeclareLaunchArgument(
|
| 31 |
+
'filled',
|
| 32 |
+
default_value='true',
|
| 33 |
+
description='Display shelves as filled transparent boxes (true/false)'
|
| 34 |
+
)
|
| 35 |
+
|
| 36 |
+
shelf_alpha_arg = DeclareLaunchArgument(
|
| 37 |
+
'alpha',
|
| 38 |
+
default_value='0.3',
|
| 39 |
+
description='Transparency level for filled shelves (0.0-1.0)'
|
| 40 |
+
)
|
| 41 |
+
|
| 42 |
+
# Static transform publisher for map frame
|
| 43 |
+
static_tf_node = Node(
|
| 44 |
+
package='tf2_ros',
|
| 45 |
+
executable='static_transform_publisher',
|
| 46 |
+
name='map_tf_publisher',
|
| 47 |
+
arguments=['0', '0', '0', '0', '0', '0', 'world', 'map'],
|
| 48 |
+
output='screen',
|
| 49 |
+
)
|
| 50 |
+
|
| 51 |
+
# Layout visualizer node with optional filled shelves arguments
|
| 52 |
+
layout_visualizer_node = Node(
|
| 53 |
+
package='db_loader',
|
| 54 |
+
executable='layout_visualizer',
|
| 55 |
+
name='layout_visualizer',
|
| 56 |
+
output='screen',
|
| 57 |
+
arguments=[
|
| 58 |
+
'--filled',
|
| 59 |
+
'--alpha',
|
| 60 |
+
LaunchConfiguration('alpha')
|
| 61 |
+
],
|
| 62 |
+
condition=IfCondition(
|
| 63 |
+
PythonExpression([
|
| 64 |
+
'"', LaunchConfiguration('filled'), '" == "true"'
|
| 65 |
+
])
|
| 66 |
+
),
|
| 67 |
+
)
|
| 68 |
+
|
| 69 |
+
# Layout visualizer node WITHOUT filled shelves (default)
|
| 70 |
+
layout_visualizer_wireframe_node = Node(
|
| 71 |
+
package='db_loader',
|
| 72 |
+
executable='layout_visualizer',
|
| 73 |
+
name='layout_visualizer',
|
| 74 |
+
output='screen',
|
| 75 |
+
condition=IfCondition(
|
| 76 |
+
PythonExpression([
|
| 77 |
+
'"', LaunchConfiguration('filled'), '" != "true"'
|
| 78 |
+
])
|
| 79 |
+
),
|
| 80 |
+
)
|
| 81 |
+
|
| 82 |
+
# RViz2 (only launches if rviz_config is provided)
|
| 83 |
+
rviz_node = Node(
|
| 84 |
+
package='rviz2',
|
| 85 |
+
executable='rviz2',
|
| 86 |
+
name='rviz2',
|
| 87 |
+
output='screen',
|
| 88 |
+
arguments=['-d', LaunchConfiguration('rviz_config')],
|
| 89 |
+
condition=IfCondition(
|
| 90 |
+
PythonExpression([
|
| 91 |
+
'"', LaunchConfiguration('rviz_config'), '" != ""'
|
| 92 |
+
])
|
| 93 |
+
),
|
| 94 |
+
)
|
| 95 |
+
|
| 96 |
+
# Layout publisher node (DELAYED to ensure subscribers are ready)
|
| 97 |
+
layout_publisher_node = Node(
|
| 98 |
+
package='db_loader',
|
| 99 |
+
executable='layout_publisher',
|
| 100 |
+
name='layout_publisher',
|
| 101 |
+
output='screen',
|
| 102 |
+
arguments=[LaunchConfiguration('json_file')],
|
| 103 |
+
condition=IfCondition(
|
| 104 |
+
PythonExpression([
|
| 105 |
+
'"', LaunchConfiguration('json_file'), '" != ""'
|
| 106 |
+
])
|
| 107 |
+
),
|
| 108 |
+
)
|
| 109 |
+
|
| 110 |
+
# Wrap layout publisher in TimerAction to delay its start
|
| 111 |
+
delayed_layout_publisher = TimerAction(
|
| 112 |
+
period=LaunchConfiguration('publisher_delay'),
|
| 113 |
+
actions=[layout_publisher_node]
|
| 114 |
+
)
|
| 115 |
+
|
| 116 |
+
return LaunchDescription([
|
| 117 |
+
json_file_arg,
|
| 118 |
+
rviz_config_arg,
|
| 119 |
+
publisher_delay_arg,
|
| 120 |
+
filled_shelves_arg,
|
| 121 |
+
shelf_alpha_arg,
|
| 122 |
+
static_tf_node,
|
| 123 |
+
layout_visualizer_node,
|
| 124 |
+
layout_visualizer_wireframe_node,
|
| 125 |
+
rviz_node,
|
| 126 |
+
delayed_layout_publisher,
|
| 127 |
+
])
|
keypoint-db/ws/src/db_loader/package.xml
ADDED
|
@@ -0,0 +1,26 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0"?>
|
| 2 |
+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
| 3 |
+
<package format="3">
|
| 4 |
+
<name>db_loader</name>
|
| 5 |
+
<version>0.0.0</version>
|
| 6 |
+
<description>TODO: Package description</description>
|
| 7 |
+
<maintainer email="user@todo.todo">user</maintainer>
|
| 8 |
+
<license>TODO: License declaration</license>
|
| 9 |
+
|
| 10 |
+
<depend>rclpy</depend>
|
| 11 |
+
<depend>db_loader_msgs</depend>
|
| 12 |
+
|
| 13 |
+
<depend>std_msgs</depend>
|
| 14 |
+
<depend>visualization_msgs</depend>
|
| 15 |
+
<depend>geometry_msgs</depend>
|
| 16 |
+
<depend>tf2_ros</depend>
|
| 17 |
+
|
| 18 |
+
<test_depend>ament_copyright</test_depend>
|
| 19 |
+
<test_depend>ament_flake8</test_depend>
|
| 20 |
+
<test_depend>ament_pep257</test_depend>
|
| 21 |
+
<test_depend>python3-pytest</test_depend>
|
| 22 |
+
|
| 23 |
+
<export>
|
| 24 |
+
<build_type>ament_python</build_type>
|
| 25 |
+
</export>
|
| 26 |
+
</package>
|
keypoint-db/ws/src/db_loader/resource/db_loader
ADDED
|
File without changes
|
keypoint-db/ws/src/db_loader/rviz/layout_view.rviz
ADDED
|
@@ -0,0 +1,278 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
Panels:
|
| 2 |
+
- Class: rviz_common/Displays
|
| 3 |
+
Help Height: 78
|
| 4 |
+
Name: Displays
|
| 5 |
+
Property Tree Widget:
|
| 6 |
+
Expanded:
|
| 7 |
+
- /Global Options1
|
| 8 |
+
- /Status1
|
| 9 |
+
- /MarkerArray1
|
| 10 |
+
- /MarkerArray1/Topic1
|
| 11 |
+
- /MarkerArray1/Namespaces1
|
| 12 |
+
- /MarkerArray2
|
| 13 |
+
- /MarkerArray2/Topic1
|
| 14 |
+
- /MarkerArray2/Namespaces1
|
| 15 |
+
- /MarkerArray3
|
| 16 |
+
- /MarkerArray3/Topic1
|
| 17 |
+
- /MarkerArray3/Namespaces1
|
| 18 |
+
Splitter Ratio: 0.5
|
| 19 |
+
Tree Height: 872
|
| 20 |
+
- Class: rviz_common/Selection
|
| 21 |
+
Name: Selection
|
| 22 |
+
- Class: rviz_common/Tool Properties
|
| 23 |
+
Expanded:
|
| 24 |
+
- /2D Goal Pose1
|
| 25 |
+
- /Publish Point1
|
| 26 |
+
Name: Tool Properties
|
| 27 |
+
Splitter Ratio: 0.5886790156364441
|
| 28 |
+
- Class: rviz_common/Views
|
| 29 |
+
Expanded:
|
| 30 |
+
- /Current View1
|
| 31 |
+
- /Current View1/Focal Point1
|
| 32 |
+
Name: Views
|
| 33 |
+
Splitter Ratio: 0.5
|
| 34 |
+
- Class: rviz_common/Time
|
| 35 |
+
Experimental: false
|
| 36 |
+
Name: Time
|
| 37 |
+
SyncMode: 0
|
| 38 |
+
SyncSource: ""
|
| 39 |
+
Visualization Manager:
|
| 40 |
+
Class: ""
|
| 41 |
+
Displays:
|
| 42 |
+
- Alpha: 0.5
|
| 43 |
+
Cell Size: 1
|
| 44 |
+
Class: rviz_default_plugins/Grid
|
| 45 |
+
Color: 160; 160; 164
|
| 46 |
+
Enabled: true
|
| 47 |
+
Line Style:
|
| 48 |
+
Line Width: 0.029999999329447746
|
| 49 |
+
Value: Lines
|
| 50 |
+
Name: Grid
|
| 51 |
+
Normal Cell Count: 0
|
| 52 |
+
Offset:
|
| 53 |
+
X: 0
|
| 54 |
+
Y: 0
|
| 55 |
+
Z: 0
|
| 56 |
+
Plane: XY
|
| 57 |
+
Plane Cell Count: 10
|
| 58 |
+
Reference Frame: <Fixed Frame>
|
| 59 |
+
Value: true
|
| 60 |
+
- Class: rviz_default_plugins/MarkerArray
|
| 61 |
+
Enabled: true
|
| 62 |
+
Name: MarkerArray
|
| 63 |
+
Namespaces:
|
| 64 |
+
exits: true
|
| 65 |
+
perimeters: true
|
| 66 |
+
shelf_labels: true
|
| 67 |
+
shelf_normals: true
|
| 68 |
+
shelves_filled: true
|
| 69 |
+
Topic:
|
| 70 |
+
Depth: 5
|
| 71 |
+
Durability Policy: Volatile
|
| 72 |
+
History Policy: Keep Last
|
| 73 |
+
Reliability Policy: Reliable
|
| 74 |
+
Value: /layout_markers
|
| 75 |
+
Value: true
|
| 76 |
+
- Class: rviz_default_plugins/MarkerArray
|
| 77 |
+
Enabled: true
|
| 78 |
+
Name: MarkerArray
|
| 79 |
+
Namespaces:
|
| 80 |
+
{}
|
| 81 |
+
Topic:
|
| 82 |
+
Depth: 5
|
| 83 |
+
Durability Policy: Volatile
|
| 84 |
+
History Policy: Keep Last
|
| 85 |
+
Reliability Policy: Reliable
|
| 86 |
+
Value: /trajectory_markers
|
| 87 |
+
Value: true
|
| 88 |
+
- Class: rviz_default_plugins/MarkerArray
|
| 89 |
+
Enabled: true
|
| 90 |
+
Name: MarkerArray
|
| 91 |
+
Namespaces:
|
| 92 |
+
bones_0517f65b3c75: true
|
| 93 |
+
bones_0b07ef703ff5: true
|
| 94 |
+
bones_123f861f40f3: true
|
| 95 |
+
bones_1bbc027eefa9: true
|
| 96 |
+
bones_27f426e5a557: true
|
| 97 |
+
bones_2f4dd05a7245: true
|
| 98 |
+
bones_41a82347ec7f: true
|
| 99 |
+
bones_4c8fd32b9cb1: true
|
| 100 |
+
bones_5eb2934bdcdb: true
|
| 101 |
+
bones_608b25ee75ee: true
|
| 102 |
+
bones_6851191f2665: true
|
| 103 |
+
bones_6edab2f72299: true
|
| 104 |
+
bones_762cd03e1d6c: true
|
| 105 |
+
bones_7d5ddf3a2aee: true
|
| 106 |
+
bones_829da41cc1ff: true
|
| 107 |
+
bones_8770c5602760: true
|
| 108 |
+
bones_9c41688ab5d3: true
|
| 109 |
+
bones_9cb974ac6ef0: true
|
| 110 |
+
bones_ab00e53fc02c: true
|
| 111 |
+
bones_abe1d799c0a4: true
|
| 112 |
+
bones_b38f535c4d54: true
|
| 113 |
+
bones_bbf6931d3aed: true
|
| 114 |
+
bones_bc979d823976: true
|
| 115 |
+
bones_bde273497bef: true
|
| 116 |
+
bones_d759ac1884c2: true
|
| 117 |
+
bones_de15e3f664fe: true
|
| 118 |
+
bones_def60a8e631b: true
|
| 119 |
+
bones_e61be4b65499: true
|
| 120 |
+
bones_f4c6b95ec893: true
|
| 121 |
+
bones_f8303beacac9: true
|
| 122 |
+
bones_f8e17e4034fa: true
|
| 123 |
+
bones_fd86fa155639: true
|
| 124 |
+
keypoints_0517f65b3c75: true
|
| 125 |
+
keypoints_0b07ef703ff5: true
|
| 126 |
+
keypoints_123f861f40f3: true
|
| 127 |
+
keypoints_1bbc027eefa9: true
|
| 128 |
+
keypoints_27f426e5a557: true
|
| 129 |
+
keypoints_2f4dd05a7245: true
|
| 130 |
+
keypoints_41a82347ec7f: true
|
| 131 |
+
keypoints_4c8fd32b9cb1: true
|
| 132 |
+
keypoints_5eb2934bdcdb: true
|
| 133 |
+
keypoints_608b25ee75ee: true
|
| 134 |
+
keypoints_6851191f2665: true
|
| 135 |
+
keypoints_6edab2f72299: true
|
| 136 |
+
keypoints_762cd03e1d6c: true
|
| 137 |
+
keypoints_7d5ddf3a2aee: true
|
| 138 |
+
keypoints_829da41cc1ff: true
|
| 139 |
+
keypoints_8770c5602760: true
|
| 140 |
+
keypoints_9c41688ab5d3: true
|
| 141 |
+
keypoints_9cb974ac6ef0: true
|
| 142 |
+
keypoints_ab00e53fc02c: true
|
| 143 |
+
keypoints_abe1d799c0a4: true
|
| 144 |
+
keypoints_b38f535c4d54: true
|
| 145 |
+
keypoints_bbf6931d3aed: true
|
| 146 |
+
keypoints_bc979d823976: true
|
| 147 |
+
keypoints_bde273497bef: true
|
| 148 |
+
keypoints_d759ac1884c2: true
|
| 149 |
+
keypoints_de15e3f664fe: true
|
| 150 |
+
keypoints_def60a8e631b: true
|
| 151 |
+
keypoints_e61be4b65499: true
|
| 152 |
+
keypoints_f4c6b95ec893: true
|
| 153 |
+
keypoints_f8303beacac9: true
|
| 154 |
+
keypoints_f8e17e4034fa: true
|
| 155 |
+
keypoints_fd86fa155639: true
|
| 156 |
+
labels_0517f65b3c75: true
|
| 157 |
+
labels_0b07ef703ff5: true
|
| 158 |
+
labels_123f861f40f3: true
|
| 159 |
+
labels_1bbc027eefa9: true
|
| 160 |
+
labels_27f426e5a557: true
|
| 161 |
+
labels_2f4dd05a7245: true
|
| 162 |
+
labels_41a82347ec7f: true
|
| 163 |
+
labels_4c8fd32b9cb1: true
|
| 164 |
+
labels_5eb2934bdcdb: true
|
| 165 |
+
labels_608b25ee75ee: true
|
| 166 |
+
labels_6851191f2665: true
|
| 167 |
+
labels_6edab2f72299: true
|
| 168 |
+
labels_762cd03e1d6c: true
|
| 169 |
+
labels_7d5ddf3a2aee: true
|
| 170 |
+
labels_829da41cc1ff: true
|
| 171 |
+
labels_8770c5602760: true
|
| 172 |
+
labels_9c41688ab5d3: true
|
| 173 |
+
labels_9cb974ac6ef0: true
|
| 174 |
+
labels_ab00e53fc02c: true
|
| 175 |
+
labels_abe1d799c0a4: true
|
| 176 |
+
labels_b38f535c4d54: true
|
| 177 |
+
labels_bbf6931d3aed: true
|
| 178 |
+
labels_bc979d823976: true
|
| 179 |
+
labels_bde273497bef: true
|
| 180 |
+
labels_d759ac1884c2: true
|
| 181 |
+
labels_de15e3f664fe: true
|
| 182 |
+
labels_def60a8e631b: true
|
| 183 |
+
labels_e61be4b65499: true
|
| 184 |
+
labels_f4c6b95ec893: true
|
| 185 |
+
labels_f8303beacac9: true
|
| 186 |
+
labels_f8e17e4034fa: true
|
| 187 |
+
labels_fd86fa155639: true
|
| 188 |
+
Topic:
|
| 189 |
+
Depth: 1
|
| 190 |
+
Durability Policy: Volatile
|
| 191 |
+
History Policy: Keep Last
|
| 192 |
+
Reliability Policy: Reliable
|
| 193 |
+
Value: /skeleton_markers
|
| 194 |
+
Value: true
|
| 195 |
+
Enabled: true
|
| 196 |
+
Global Options:
|
| 197 |
+
Background Color: 207; 207; 207
|
| 198 |
+
Fixed Frame: map
|
| 199 |
+
Frame Rate: 30
|
| 200 |
+
Name: root
|
| 201 |
+
Tools:
|
| 202 |
+
- Class: rviz_default_plugins/Interact
|
| 203 |
+
Hide Inactive Objects: true
|
| 204 |
+
- Class: rviz_default_plugins/MoveCamera
|
| 205 |
+
- Class: rviz_default_plugins/Select
|
| 206 |
+
- Class: rviz_default_plugins/FocusCamera
|
| 207 |
+
- Class: rviz_default_plugins/Measure
|
| 208 |
+
Line color: 128; 128; 0
|
| 209 |
+
- Class: rviz_default_plugins/SetInitialPose
|
| 210 |
+
Covariance x: 0.25
|
| 211 |
+
Covariance y: 0.25
|
| 212 |
+
Covariance yaw: 0.06853891909122467
|
| 213 |
+
Topic:
|
| 214 |
+
Depth: 5
|
| 215 |
+
Durability Policy: Volatile
|
| 216 |
+
History Policy: Keep Last
|
| 217 |
+
Reliability Policy: Reliable
|
| 218 |
+
Value: /initialpose
|
| 219 |
+
- Class: rviz_default_plugins/SetGoal
|
| 220 |
+
Topic:
|
| 221 |
+
Depth: 5
|
| 222 |
+
Durability Policy: Volatile
|
| 223 |
+
History Policy: Keep Last
|
| 224 |
+
Reliability Policy: Reliable
|
| 225 |
+
Value: /goal_pose
|
| 226 |
+
- Class: rviz_default_plugins/PublishPoint
|
| 227 |
+
Single click: true
|
| 228 |
+
Topic:
|
| 229 |
+
Depth: 5
|
| 230 |
+
Durability Policy: Volatile
|
| 231 |
+
History Policy: Keep Last
|
| 232 |
+
Reliability Policy: Reliable
|
| 233 |
+
Value: /clicked_point
|
| 234 |
+
Transformation:
|
| 235 |
+
Current:
|
| 236 |
+
Class: rviz_default_plugins/TF
|
| 237 |
+
Value: true
|
| 238 |
+
Views:
|
| 239 |
+
Current:
|
| 240 |
+
Class: rviz_default_plugins/XYOrbit
|
| 241 |
+
Distance: 13.364635467529297
|
| 242 |
+
Enable Stereo Rendering:
|
| 243 |
+
Stereo Eye Separation: 0.05999999865889549
|
| 244 |
+
Stereo Focal Distance: 1
|
| 245 |
+
Swap Stereo Eyes: false
|
| 246 |
+
Value: false
|
| 247 |
+
Focal Point:
|
| 248 |
+
X: 5.0003252029418945
|
| 249 |
+
Y: 2.261509895324707
|
| 250 |
+
Z: 1.430511474609375e-05
|
| 251 |
+
Focal Shape Fixed Size: false
|
| 252 |
+
Focal Shape Size: 0.05000000074505806
|
| 253 |
+
Invert Z Axis: false
|
| 254 |
+
Name: Current View
|
| 255 |
+
Near Clip Distance: 0.009999999776482582
|
| 256 |
+
Pitch: 1.1153980493545532
|
| 257 |
+
Target Frame: map
|
| 258 |
+
Value: XYOrbit (rviz_default_plugins)
|
| 259 |
+
Yaw: 4.698578834533691
|
| 260 |
+
Saved: ~
|
| 261 |
+
Window Geometry:
|
| 262 |
+
Displays:
|
| 263 |
+
collapsed: true
|
| 264 |
+
Height: 1163
|
| 265 |
+
Hide Left Dock: true
|
| 266 |
+
Hide Right Dock: true
|
| 267 |
+
QMainWindow State: 000000ff00000000fd000000040000000000000156000003f1fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003b000003f1000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003f1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000003f1000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000025300fffffffb0000000800540069006d0065010000000000000450000000000000000000000780000003f100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
| 268 |
+
Selection:
|
| 269 |
+
collapsed: false
|
| 270 |
+
Time:
|
| 271 |
+
collapsed: false
|
| 272 |
+
Tool Properties:
|
| 273 |
+
collapsed: false
|
| 274 |
+
Views:
|
| 275 |
+
collapsed: true
|
| 276 |
+
Width: 1920
|
| 277 |
+
X: 3840
|
| 278 |
+
Y: 0
|
keypoint-db/ws/src/db_loader/rviz/layout_view_rviz
ADDED
|
@@ -0,0 +1,133 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
Panels:
|
| 2 |
+
- Class: rviz_common/Displays
|
| 3 |
+
Help Height: 78
|
| 4 |
+
Name: Displays
|
| 5 |
+
Property Tree Widget:
|
| 6 |
+
Expanded:
|
| 7 |
+
- /Global Options1
|
| 8 |
+
- /Status1
|
| 9 |
+
- /Layout Markers1
|
| 10 |
+
- /MarkerArray1
|
| 11 |
+
Splitter Ratio: 0.5
|
| 12 |
+
Tree Height: 1308
|
| 13 |
+
- Class: rviz_common/Views
|
| 14 |
+
Expanded:
|
| 15 |
+
- /Current View1
|
| 16 |
+
Name: Views
|
| 17 |
+
Splitter Ratio: 0.5
|
| 18 |
+
Visualization Manager:
|
| 19 |
+
Class: ""
|
| 20 |
+
Displays:
|
| 21 |
+
- Alpha: 0.5
|
| 22 |
+
Cell Size: 1
|
| 23 |
+
Class: rviz_default_plugins/Grid
|
| 24 |
+
Color: 160; 160; 164
|
| 25 |
+
Enabled: true
|
| 26 |
+
Line Style:
|
| 27 |
+
Line Width: 0.029999999329447746
|
| 28 |
+
Value: Lines
|
| 29 |
+
Name: Grid
|
| 30 |
+
Normal Cell Count: 0
|
| 31 |
+
Offset:
|
| 32 |
+
X: 0
|
| 33 |
+
Y: 0
|
| 34 |
+
Z: 0
|
| 35 |
+
Plane: XY
|
| 36 |
+
Plane Cell Count: 50
|
| 37 |
+
Reference Frame: <Fixed Frame>
|
| 38 |
+
Value: true
|
| 39 |
+
- Class: rviz_default_plugins/MarkerArray
|
| 40 |
+
Enabled: true
|
| 41 |
+
Name: Layout Markers
|
| 42 |
+
Namespaces:
|
| 43 |
+
exits: true
|
| 44 |
+
perimeters: true
|
| 45 |
+
shelf_labels: true
|
| 46 |
+
shelf_normals: true
|
| 47 |
+
shelves: true
|
| 48 |
+
Topic:
|
| 49 |
+
Depth: 5
|
| 50 |
+
Durability Policy: Volatile
|
| 51 |
+
History Policy: Keep Last
|
| 52 |
+
Reliability Policy: Reliable
|
| 53 |
+
Value: /layout_markers
|
| 54 |
+
Value: true
|
| 55 |
+
- Class: rviz_default_plugins/MarkerArray
|
| 56 |
+
Enabled: true
|
| 57 |
+
Name: MarkerArray
|
| 58 |
+
Namespaces:
|
| 59 |
+
exits: true
|
| 60 |
+
perimeters: true
|
| 61 |
+
shelf_labels: true
|
| 62 |
+
shelf_normals: true
|
| 63 |
+
shelves: true
|
| 64 |
+
Topic:
|
| 65 |
+
Depth: 5
|
| 66 |
+
Durability Policy: Volatile
|
| 67 |
+
History Policy: Keep Last
|
| 68 |
+
Reliability Policy: Reliable
|
| 69 |
+
Value: /layout_markers
|
| 70 |
+
Value: true
|
| 71 |
+
Enabled: true
|
| 72 |
+
Global Options:
|
| 73 |
+
Background Color: 162; 162; 162
|
| 74 |
+
Fixed Frame: map
|
| 75 |
+
Frame Rate: 30
|
| 76 |
+
Name: root
|
| 77 |
+
Tools:
|
| 78 |
+
- Class: rviz_default_plugins/MoveCamera
|
| 79 |
+
- Class: rviz_default_plugins/Select
|
| 80 |
+
- Class: rviz_default_plugins/FocusCamera
|
| 81 |
+
- Class: rviz_default_plugins/Measure
|
| 82 |
+
Line color: 128; 128; 0
|
| 83 |
+
Transformation:
|
| 84 |
+
Current:
|
| 85 |
+
Class: rviz_default_plugins/TF
|
| 86 |
+
Value: true
|
| 87 |
+
Views:
|
| 88 |
+
Current:
|
| 89 |
+
Angle: 0.039999958127737045
|
| 90 |
+
Class: rviz_default_plugins/TopDownOrtho
|
| 91 |
+
Enable Stereo Rendering:
|
| 92 |
+
Stereo Eye Separation: 0.05999999865889549
|
| 93 |
+
Stereo Focal Distance: 1
|
| 94 |
+
Swap Stereo Eyes: false
|
| 95 |
+
Value: false
|
| 96 |
+
Invert Z Axis: false
|
| 97 |
+
Name: Current View
|
| 98 |
+
Near Clip Distance: 0.009999999776482582
|
| 99 |
+
Scale: 119.80030059814453
|
| 100 |
+
Target Frame: <Fixed Frame>
|
| 101 |
+
Value: TopDownOrtho (rviz_default_plugins)
|
| 102 |
+
X: 5.269617557525635
|
| 103 |
+
Y: 4.5275774002075195
|
| 104 |
+
Saved: ~
|
| 105 |
+
Window Geometry:
|
| 106 |
+
Displays:
|
| 107 |
+
collapsed: false
|
| 108 |
+
Height: 1531
|
| 109 |
+
Hide Left Dock: false
|
| 110 |
+
Hide Right Dock: false
|
| 111 |
+
QMainWindow State: 000000ff00000000fd000000040000000000000156000005a5fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000000000000000fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000005a5000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000005a5fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000005a5000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000000000000000fb0000000800540069006d006501000000000000045000000000000000000000074d000005a500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
| 112 |
+
Views:
|
| 113 |
+
collapsed: false
|
| 114 |
+
Width: 2494
|
| 115 |
+
X: 66
|
| 116 |
+
Y: 32
|
| 117 |
+
|
| 118 |
+
|
| 119 |
+
|
| 120 |
+
|
| 121 |
+
|
| 122 |
+
- Class: rviz_default_plugins/MarkerArray
|
| 123 |
+
Enabled: true
|
| 124 |
+
Name: Trajectory Markers
|
| 125 |
+
Namespaces:
|
| 126 |
+
{}
|
| 127 |
+
Topic:
|
| 128 |
+
Depth: 5
|
| 129 |
+
Durability Policy: Volatile
|
| 130 |
+
History Policy: Keep Last
|
| 131 |
+
Reliability Policy: Reliable
|
| 132 |
+
Value: /trajectory_markers
|
| 133 |
+
Value: true
|
keypoint-db/ws/src/db_loader/setup.cfg
ADDED
|
@@ -0,0 +1,4 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
[develop]
|
| 2 |
+
script_dir=$base/lib/db_loader
|
| 3 |
+
[install]
|
| 4 |
+
install_scripts=$base/lib/db_loader
|
keypoint-db/ws/src/db_loader/setup.py
ADDED
|
@@ -0,0 +1,40 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import os
|
| 2 |
+
from glob import glob
|
| 3 |
+
from setuptools import find_packages, setup
|
| 4 |
+
|
| 5 |
+
package_name = 'db_loader'
|
| 6 |
+
|
| 7 |
+
setup(
|
| 8 |
+
name=package_name,
|
| 9 |
+
version='0.0.0',
|
| 10 |
+
packages=find_packages(exclude=['test']),
|
| 11 |
+
data_files=[
|
| 12 |
+
('share/ament_index/resource_index/packages',
|
| 13 |
+
['resource/' + package_name]),
|
| 14 |
+
('share/' + package_name, ['package.xml']),
|
| 15 |
+
(os.path.join('share', package_name, 'launch'), glob('launch/*.py')),
|
| 16 |
+
(os.path.join('share', package_name, 'rviz'), glob('rviz/*.rviz')),
|
| 17 |
+
|
| 18 |
+
|
| 19 |
+
|
| 20 |
+
],
|
| 21 |
+
install_requires=['setuptools'],
|
| 22 |
+
zip_safe=True,
|
| 23 |
+
maintainer='user',
|
| 24 |
+
maintainer_email='user@todo.todo',
|
| 25 |
+
description='TODO: Package description',
|
| 26 |
+
license='TODO: License declaration',
|
| 27 |
+
extras_require={
|
| 28 |
+
'test': [
|
| 29 |
+
'pytest',
|
| 30 |
+
],
|
| 31 |
+
},
|
| 32 |
+
entry_points={
|
| 33 |
+
'console_scripts': [
|
| 34 |
+
'layout_publisher = db_loader.layout_publisher:main',
|
| 35 |
+
'layout_visualizer = db_loader.layout_visualizer:main',
|
| 36 |
+
'keypoint_publisher = db_loader.keypoint_publisher:main',
|
| 37 |
+
'index_keypoint_publisher = db_loader.index_keypoint_publisher:main',
|
| 38 |
+
],
|
| 39 |
+
},
|
| 40 |
+
)
|
keypoint-db/ws/src/db_loader/test/test_copyright.py
ADDED
|
@@ -0,0 +1,25 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
| 2 |
+
#
|
| 3 |
+
# Licensed under the Apache License, Version 2.0 (the "License");
|
| 4 |
+
# you may not use this file except in compliance with the License.
|
| 5 |
+
# You may obtain a copy of the License at
|
| 6 |
+
#
|
| 7 |
+
# http://www.apache.org/licenses/LICENSE-2.0
|
| 8 |
+
#
|
| 9 |
+
# Unless required by applicable law or agreed to in writing, software
|
| 10 |
+
# distributed under the License is distributed on an "AS IS" BASIS,
|
| 11 |
+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
| 12 |
+
# See the License for the specific language governing permissions and
|
| 13 |
+
# limitations under the License.
|
| 14 |
+
|
| 15 |
+
from ament_copyright.main import main
|
| 16 |
+
import pytest
|
| 17 |
+
|
| 18 |
+
|
| 19 |
+
# Remove the `skip` decorator once the source file(s) have a copyright header
|
| 20 |
+
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
|
| 21 |
+
@pytest.mark.copyright
|
| 22 |
+
@pytest.mark.linter
|
| 23 |
+
def test_copyright():
|
| 24 |
+
rc = main(argv=['.', 'test'])
|
| 25 |
+
assert rc == 0, 'Found errors'
|
keypoint-db/ws/src/db_loader/test/test_flake8.py
ADDED
|
@@ -0,0 +1,25 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
# Copyright 2017 Open Source Robotics Foundation, Inc.
|
| 2 |
+
#
|
| 3 |
+
# Licensed under the Apache License, Version 2.0 (the "License");
|
| 4 |
+
# you may not use this file except in compliance with the License.
|
| 5 |
+
# You may obtain a copy of the License at
|
| 6 |
+
#
|
| 7 |
+
# http://www.apache.org/licenses/LICENSE-2.0
|
| 8 |
+
#
|
| 9 |
+
# Unless required by applicable law or agreed to in writing, software
|
| 10 |
+
# distributed under the License is distributed on an "AS IS" BASIS,
|
| 11 |
+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
| 12 |
+
# See the License for the specific language governing permissions and
|
| 13 |
+
# limitations under the License.
|
| 14 |
+
|
| 15 |
+
from ament_flake8.main import main_with_errors
|
| 16 |
+
import pytest
|
| 17 |
+
|
| 18 |
+
|
| 19 |
+
@pytest.mark.flake8
|
| 20 |
+
@pytest.mark.linter
|
| 21 |
+
def test_flake8():
|
| 22 |
+
rc, errors = main_with_errors(argv=[])
|
| 23 |
+
assert rc == 0, \
|
| 24 |
+
'Found %d code style errors / warnings:\n' % len(errors) + \
|
| 25 |
+
'\n'.join(errors)
|
keypoint-db/ws/src/db_loader/test/test_pep257.py
ADDED
|
@@ -0,0 +1,23 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
| 2 |
+
#
|
| 3 |
+
# Licensed under the Apache License, Version 2.0 (the "License");
|
| 4 |
+
# you may not use this file except in compliance with the License.
|
| 5 |
+
# You may obtain a copy of the License at
|
| 6 |
+
#
|
| 7 |
+
# http://www.apache.org/licenses/LICENSE-2.0
|
| 8 |
+
#
|
| 9 |
+
# Unless required by applicable law or agreed to in writing, software
|
| 10 |
+
# distributed under the License is distributed on an "AS IS" BASIS,
|
| 11 |
+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
| 12 |
+
# See the License for the specific language governing permissions and
|
| 13 |
+
# limitations under the License.
|
| 14 |
+
|
| 15 |
+
from ament_pep257.main import main
|
| 16 |
+
import pytest
|
| 17 |
+
|
| 18 |
+
|
| 19 |
+
@pytest.mark.linter
|
| 20 |
+
@pytest.mark.pep257
|
| 21 |
+
def test_pep257():
|
| 22 |
+
rc = main(argv=['.', 'test'])
|
| 23 |
+
assert rc == 0, 'Found code style errors / warnings'
|
keypoint-db/ws/src/db_loader_msgs/CMakeLists.txt
ADDED
|
@@ -0,0 +1,21 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
cmake_minimum_required(VERSION 3.8)
|
| 2 |
+
project(db_loader_msgs)
|
| 3 |
+
|
| 4 |
+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
| 5 |
+
add_compile_options(-Wall -Wextra -Wpedantic)
|
| 6 |
+
endif()
|
| 7 |
+
|
| 8 |
+
# find dependencies
|
| 9 |
+
find_package(ament_cmake REQUIRED)
|
| 10 |
+
find_package(rosidl_default_generators REQUIRED)
|
| 11 |
+
find_package(std_msgs REQUIRED)
|
| 12 |
+
|
| 13 |
+
# Generate interfaces
|
| 14 |
+
rosidl_generate_interfaces(${PROJECT_NAME}
|
| 15 |
+
"msg/Skeleton.msg"
|
| 16 |
+
DEPENDENCIES std_msgs
|
| 17 |
+
)
|
| 18 |
+
|
| 19 |
+
ament_export_dependencies(rosidl_default_runtime)
|
| 20 |
+
|
| 21 |
+
ament_package()
|
keypoint-db/ws/src/db_loader_msgs/msg/Skeleton.msg
ADDED
|
@@ -0,0 +1,74 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
# Skeleton keypoints for a single person
|
| 2 |
+
string person_track_id
|
| 3 |
+
float64 timestamp
|
| 4 |
+
|
| 5 |
+
# Head
|
| 6 |
+
float64 top_of_head_x
|
| 7 |
+
float64 top_of_head_y
|
| 8 |
+
float64 top_of_head_z
|
| 9 |
+
|
| 10 |
+
# Neck
|
| 11 |
+
float64 neck_x
|
| 12 |
+
float64 neck_y
|
| 13 |
+
float64 neck_z
|
| 14 |
+
|
| 15 |
+
# Right arm
|
| 16 |
+
float64 right_shoulder_x
|
| 17 |
+
float64 right_shoulder_y
|
| 18 |
+
float64 right_shoulder_z
|
| 19 |
+
float64 right_elbow_x
|
| 20 |
+
float64 right_elbow_y
|
| 21 |
+
float64 right_elbow_z
|
| 22 |
+
float64 right_wrist_x
|
| 23 |
+
float64 right_wrist_y
|
| 24 |
+
float64 right_wrist_z
|
| 25 |
+
float64 right_hand_x
|
| 26 |
+
float64 right_hand_y
|
| 27 |
+
float64 right_hand_z
|
| 28 |
+
|
| 29 |
+
# Left arm
|
| 30 |
+
float64 left_shoulder_x
|
| 31 |
+
float64 left_shoulder_y
|
| 32 |
+
float64 left_shoulder_z
|
| 33 |
+
float64 left_elbow_x
|
| 34 |
+
float64 left_elbow_y
|
| 35 |
+
float64 left_elbow_z
|
| 36 |
+
float64 left_wrist_x
|
| 37 |
+
float64 left_wrist_y
|
| 38 |
+
float64 left_wrist_z
|
| 39 |
+
float64 left_hand_x
|
| 40 |
+
float64 left_hand_y
|
| 41 |
+
float64 left_hand_z
|
| 42 |
+
|
| 43 |
+
# Waist
|
| 44 |
+
float64 middle_of_waist_x
|
| 45 |
+
float64 middle_of_waist_y
|
| 46 |
+
float64 middle_of_waist_z
|
| 47 |
+
|
| 48 |
+
# Right leg
|
| 49 |
+
float64 right_hip_x
|
| 50 |
+
float64 right_hip_y
|
| 51 |
+
float64 right_hip_z
|
| 52 |
+
float64 right_knee_x
|
| 53 |
+
float64 right_knee_y
|
| 54 |
+
float64 right_knee_z
|
| 55 |
+
float64 right_ankle_x
|
| 56 |
+
float64 right_ankle_y
|
| 57 |
+
float64 right_ankle_z
|
| 58 |
+
float64 right_foot_x
|
| 59 |
+
float64 right_foot_y
|
| 60 |
+
float64 right_foot_z
|
| 61 |
+
|
| 62 |
+
# Left leg
|
| 63 |
+
float64 left_hip_x
|
| 64 |
+
float64 left_hip_y
|
| 65 |
+
float64 left_hip_z
|
| 66 |
+
float64 left_knee_x
|
| 67 |
+
float64 left_knee_y
|
| 68 |
+
float64 left_knee_z
|
| 69 |
+
float64 left_ankle_x
|
| 70 |
+
float64 left_ankle_y
|
| 71 |
+
float64 left_ankle_z
|
| 72 |
+
float64 left_foot_x
|
| 73 |
+
float64 left_foot_y
|
| 74 |
+
float64 left_foot_z
|
keypoint-db/ws/src/db_loader_msgs/package.xml
ADDED
|
@@ -0,0 +1,24 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0"?>
|
| 2 |
+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
| 3 |
+
<package format="3">
|
| 4 |
+
<name>db_loader_msgs</name>
|
| 5 |
+
<version>0.0.0</version>
|
| 6 |
+
<description>Custom messages for db_loader package</description>
|
| 7 |
+
<maintainer email="user@todo.todo">user</maintainer>
|
| 8 |
+
<license>MIT</license>
|
| 9 |
+
|
| 10 |
+
<buildtool_depend>ament_cmake</buildtool_depend>
|
| 11 |
+
|
| 12 |
+
<depend>std_msgs</depend>
|
| 13 |
+
|
| 14 |
+
<build_depend>rosidl_default_generators</build_depend>
|
| 15 |
+
<exec_depend>rosidl_default_runtime</exec_depend>
|
| 16 |
+
<member_of_group>rosidl_interface_packages</member_of_group>
|
| 17 |
+
|
| 18 |
+
<test_depend>ament_lint_auto</test_depend>
|
| 19 |
+
<test_depend>ament_lint_common</test_depend>
|
| 20 |
+
|
| 21 |
+
<export>
|
| 22 |
+
<build_type>ament_cmake</build_type>
|
| 23 |
+
</export>
|
| 24 |
+
</package>
|