From b000850d689f5f356546ca6e0cf10d3e7fad3d3e Mon Sep 17 00:00:00 2001 From: pulipakaa24 Date: Sun, 15 Mar 2026 22:27:34 -0500 Subject: [PATCH] readme mini-update --- readme.md | 17 ++++++++++--- tracking_re_id/calibration/left.yaml | 24 +++++++++++++++++++ tracking_re_id/calibration/right.yaml | 24 +++++++++++++++++++ .../launch/start_cameras_only.launch.py | 9 +++++-- tracking_re_id/setup.py | 1 + 5 files changed, 70 insertions(+), 5 deletions(-) create mode 100644 tracking_re_id/calibration/left.yaml create mode 100644 tracking_re_id/calibration/right.yaml rename start_cameras_only.launch.py => tracking_re_id/launch/start_cameras_only.launch.py (89%) diff --git a/readme.md b/readme.md index 13a35c7..228927d 100644 --- a/readme.md +++ b/readme.md @@ -2,10 +2,14 @@ Repository for robust, adaptive 3D person tracking and reidentification in busy areas ## Environment Setup -**Your environment MUST have MMPOSE properly installed.** Follow the instructions below to set it up +**Next, your environment MUST have MMPOSE and the tracking_re_id ROS2 package properly installed** Follow the instructions below to set it up ```bash -#3.10 is the latest supported by MMPOSE +# wherever you want your workspace root to be (anywhere upstream of tracking_re_id): +colcon build --symlink-install +source install/setup.bash + +# 3.10 is the latest supported by MMPOSE conda create -n mmpose python=3.10 -y conda activate mmpose @@ -26,4 +30,11 @@ pip install "numpy<2" pip install "opencv-python==4.11.0.86" ``` -**This installation is referenced in each launchfile by finding the location of your conda base environment, then finding an environment named "mmpose" - if you use a different name, you must change each launch file.** \ No newline at end of file +**This installation is referenced in each launchfile by finding the location of your conda base environment, then finding an environment named "mmpose" - if you use a different name, you must change each launch file.** + +## Camera Driver / Calibration +Many nodes in the ```tracking_re_id``` package rely on the ```/stereo/left/camera_info``` and ```/stereo/right/camera_info``` topics publishing calibration data for the camera. This requires calibration to be performed, replacing ```left.yaml``` and ```right.yaml``` in ```tracking_re_id/calibration```. + +Visit https://docs.ros.org/en/jazzy/p/camera_calibration/doc/tutorial_stereo.html for instructions on running the calibration. The left and right yaml files always had ```camera_name=narrow_stereo/left``` and ```camera_name=narrow_stereo/right``` which have to be changed to ```stereo/left``` and ```stereo/right```, respectively. + +To run the camera driver after calibration has been conducted, simply execute ```ros2 launch tracking_re_id start_cameras_only.launch.py```. Running ```colcon build``` again is **NOT** required, as you should have run it with ```--symlink-install``` previously. \ No newline at end of file diff --git a/tracking_re_id/calibration/left.yaml b/tracking_re_id/calibration/left.yaml new file mode 100644 index 0000000..24bf6c1 --- /dev/null +++ b/tracking_re_id/calibration/left.yaml @@ -0,0 +1,24 @@ +# Left camera calibration file. +# Replace this with the output from your stereo calibration tool (e.g. camera_calibration ROS package). +# The file must follow the ROS camera_info YAML format consumed by camera_info_url. + +image_width: 1440 +image_height: 1080 +camera_name: left +camera_matrix: + rows: 3 + cols: 3 + data: [1, 0, 0, 0, 1, 0, 0, 0, 1] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [0, 0, 0, 0, 0] +rectification_matrix: + rows: 3 + cols: 3 + data: [1, 0, 0, 0, 1, 0, 0, 0, 1] +projection_matrix: + rows: 3 + cols: 4 + data: [1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0] diff --git a/tracking_re_id/calibration/right.yaml b/tracking_re_id/calibration/right.yaml new file mode 100644 index 0000000..f077180 --- /dev/null +++ b/tracking_re_id/calibration/right.yaml @@ -0,0 +1,24 @@ +# Right camera calibration file. +# Replace this with the output from your stereo calibration tool (e.g. camera_calibration ROS package). +# The file must follow the ROS camera_info YAML format consumed by camera_info_url. + +image_width: 1440 +image_height: 1080 +camera_name: right +camera_matrix: + rows: 3 + cols: 3 + data: [1, 0, 0, 0, 1, 0, 0, 0, 1] +distortion_model: plumb_bob +distortion_coefficients: + rows: 1 + cols: 5 + data: [0, 0, 0, 0, 0] +rectification_matrix: + rows: 3 + cols: 3 + data: [1, 0, 0, 0, 1, 0, 0, 0, 1] +projection_matrix: + rows: 3 + cols: 4 + data: [1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0] diff --git a/start_cameras_only.launch.py b/tracking_re_id/launch/start_cameras_only.launch.py similarity index 89% rename from start_cameras_only.launch.py rename to tracking_re_id/launch/start_cameras_only.launch.py index 12c55ba..62915aa 100644 --- a/start_cameras_only.launch.py +++ b/tracking_re_id/launch/start_cameras_only.launch.py @@ -11,12 +11,17 @@ RIGHT_CAMERA_NAME = 'right' def generate_launch_description(): + pkg_share = get_package_share_directory('tracking_re_id') + config_path = os.path.join( get_package_share_directory('spinnaker_camera_driver'), 'config', 'blackfly_s.yaml' ) + left_cal = 'file://' + os.path.join(pkg_share, 'calibration', 'left.yaml') + right_cal = 'file://' + os.path.join(pkg_share, 'calibration', 'right.yaml') + # ── Camera Drivers (component_container_mt) ───────────────────────── # # Both cameras share a single process because the FLIR Spinnaker SDK @@ -39,7 +44,7 @@ def generate_launch_description(): parameters=[{ 'parameter_file': config_path, 'serial_number': '25282106', - 'camera_info_url': 'file:///home/sentry/camera_ws/stereoCal/left.yaml', + 'camera_info_url': left_cal, }], extra_arguments=[{'use_intra_process_comms': True}], ), @@ -51,7 +56,7 @@ def generate_launch_description(): parameters=[{ 'parameter_file': config_path, 'serial_number': '25235293', - 'camera_info_url': 'file:///home/sentry/camera_ws/stereoCal/right.yaml', + 'camera_info_url': right_cal, }], extra_arguments=[{'use_intra_process_comms': True}], ), diff --git a/tracking_re_id/setup.py b/tracking_re_id/setup.py index 5456350..2fb1ea3 100644 --- a/tracking_re_id/setup.py +++ b/tracking_re_id/setup.py @@ -14,6 +14,7 @@ setup( ('share/' + package_name, ['package.xml']), (os.path.join('share', package_name, 'launch'), glob('launch/*.py')), (os.path.join('share', package_name, 'weights'), glob('weights/*.pth')), + (os.path.join('share', package_name, 'calibration'), glob('calibration/*.yaml')), ], install_requires=['setuptools'], zip_safe=True,