Skip to content

Commit

Permalink
Merge pull request #69 from RachelRen05/add_reid
Browse files Browse the repository at this point in the history
Add reid
  • Loading branch information
LewisLiuPub authored Mar 14, 2019
2 parents 3bf5462 + 60516f0 commit 1fd9dd4
Show file tree
Hide file tree
Showing 7 changed files with 132 additions and 9 deletions.
12 changes: 12 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ Currently, the inference feature list is supported:
|Object Detection| object detection based on SSD-based trained models.|
|Vehicle Detection| Vehicle and passenger detection based on Intel models.|
|Object Segmentation| object detection and segmentation.|
|Person Reidentification| Person Reidentification based on object detection.|

## ROS interfaces and outputs
### Topic
Expand All @@ -77,6 +78,8 @@ Currently, the inference feature list is supported:
```/ros2_openvino_toolkit/detected_objects```([object_msgs::msg::ObjectsInBoxes](https://github.com/intel/ros2_object_msgs/blob/master/msg/ObjectsInBoxes.msg))
- Object Segmentation:
```/ros2_openvino_toolkit/segmented_obejcts```([people_msgs::msg::ObjectsInMasks](https://github.com/intel/ros2_openvino_toolkit/blob/devel/people_msgs/msg/ObjectsInMasks.msg))
- Person Reidentification:
```/ros2_openvino_toolkit/reidentified_persons```([people_msgs::msg::ReidentificationStamped](https://github.com/intel/ros2_openvino_toolkit/blob/devel/people_msgs/msg/ReidentificationStamped.msg))
- Rviz Output:
```/ros2_openvino_toolkit/image_rviz```([sensor_msgs::msg::Image](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Image.msg))

Expand Down Expand Up @@ -112,6 +115,9 @@ See below pictures for the demo result snapshots.
* object segmentation input from video
![object_segmentation_demo_video](https://github.com/intel/ros2_openvino_toolkit/blob/devel/data/images/object_segmentation.gif "object segmentation demo video")

* Person Reidentification input from standard camera
![person_reidentification_demo_video](https://github.com/intel/ros2_openvino_toolkit/blob/devel/data/images/person-reidentification.gif "person reidentification demo video")

# Installation & Launching
**NOTE:** Intel releases 2 different series of OpenVINO Toolkit, we call them as [OpenSource Version](https://github.com/opencv/dldt/) and [Tarball Version](https://software.intel.com/en-us/openvino-toolkit). This guidelie uses OpenSource Version as the installation and launching example. **If you want to use Tarball version, please follow [the guide for Tarball Version](https://github.com/intel/ros2_openvino_toolkit/blob/devel/doc/BINARY_VERSION_README.md).**

Expand Down Expand Up @@ -189,6 +195,8 @@ One-step installation scripts are provided for the dependencies' installation. P
python3 downloader.py --name age-gender-recognition-retail-0013
python3 downloader.py --name emotions-recognition-retail-0003
python3 downloader.py --name head-pose-estimation-adas-0001
python3 downloader.py --name person-detection-retail-0013
python3 downloader.py --name person-reidentification-retail-0076
```
* copy label files (excute _once_)<br>
```bash
Expand Down Expand Up @@ -225,6 +233,10 @@ One-step installation scripts are provided for the dependencies' installation. P
```bash
ros2 launch dynamic_vino_sample pipeline_video.launch.py
```
* run person reidentification sample code input from StandardCamera.
```bash
ros2 launch dynamic_vino_sample pipeline_reidentification_oss.launch.py
```
* run object detection service sample code input from Image
Run image processing service:
```bash
Expand Down
Binary file added data/images/person-reidentification.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
4 changes: 4 additions & 0 deletions doc/BINARY_VERSION_README.md
Original file line number Diff line number Diff line change
Expand Up @@ -178,6 +178,10 @@ This project is a ROS2 wrapper for CV API of [OpenVINO™](https://software.inte
```bash
ros2 launch dynamic_vino_sample pipeline_video.launch.py
```
* run person reidentification sample code input from StandardCamera.
```bash
ros2 launch dynamic_vino_sample pipeline_reidentification.launch.py
```
* run object detection service sample code input from Image
Run image processing service:
```bash
Expand Down
44 changes: 44 additions & 0 deletions sample/launch/pipeline_reidentification.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# Copyright 2018 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Launch face detection and rviz."""

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
import launch_ros.actions


def generate_launch_description():
default_yaml = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'param',
'pipeline_reidentification.yaml')
default_rviz = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'launch',
'rviz/default.rviz')
return LaunchDescription([
# Openvino detection
launch_ros.actions.Node(
package='dynamic_vino_sample', node_executable='pipeline_with_params',
arguments=['-config', default_yaml],
remappings=[
('/openvino_toolkit/detected_objects', '/ros2_openvino_toolkit/detected_objects'),
('/openvino_toolkit/reidentified_persons', '/ros2_openvino_toolkit/reidentified_persons'),
('/openvino_toolkit/images', '/ros2_openvino_toolkit/image_rviz')],
output='screen'),

# Rviz
launch_ros.actions.Node(
package='rviz2', node_executable='rviz2', output='screen',
arguments=['--display-config', default_rviz]),
])
44 changes: 44 additions & 0 deletions sample/launch/pipeline_reidentification_oss.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# Copyright 2018 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Launch face detection and rviz."""

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
import launch_ros.actions


def generate_launch_description():
default_yaml = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'param',
'pipeline_reidentification_oss.yaml')
default_rviz = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'launch',
'rviz/default.rviz')
return LaunchDescription([
# Openvino detection
launch_ros.actions.Node(
package='dynamic_vino_sample', node_executable='pipeline_with_params',
arguments=['-config', default_yaml],
remappings=[
('/openvino_toolkit/detected_objects', '/ros2_openvino_toolkit/detected_objects'),
('/openvino_toolkit/reidentified_persons', '/ros2_openvino_toolkit/reidentified_persons'),
('/openvino_toolkit/images', '/ros2_openvino_toolkit/image_rviz')],
output='screen'),

# Rviz
launch_ros.actions.Node(
package='rviz2', node_executable='rviz2', output='screen',
arguments=['--display-config', default_rviz]),
])
10 changes: 1 addition & 9 deletions sample/param/pipeline_reidentification.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,21 +15,13 @@ Pipelines:
label: to/be/set/xxx.labels
batch: 1
confidence_threshold: 0.7
- name: PersonAttribsDetection
model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/person-attributes-recognition-crossroad-0031/FP32/person-attributes-recognition-crossroad-0031.xml
engine: CPU
label: to/be/set/xxx.labels
batch: 1
confidence_threshold: 0.5
outputs: [ImageWindow, RViz, RosTopic]
connects:
- left: StandardCamera
right: [ObjectDetection]
- left: ObjectDetection
right: [PersonReidentification, PersonAttribsDetection]
right: [PersonReidentification]
- left: PersonReidentification
right: [ImageWindow, RViz, RosTopic]
- left: PersonAttribsDetection
right: [ImageWindow, RViz, RosTopic]

OpenvinoCommon:
27 changes: 27 additions & 0 deletions sample/param/pipeline_reidentification_oss.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
Pipelines:
- name: object
inputs: [StandardCamera]
infers:
- name: ObjectDetection
model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml
engine: CPU
label: to/be/set/xxx.labels
batch: 1
confidence_threshold: 0.5
enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame
- name: PersonReidentification
model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml
engine: CPU
label: to/be/set/xxx.labels
batch: 1
confidence_threshold: 0.7
outputs: [ImageWindow, RViz, RosTopic]
connects:
- left: StandardCamera
right: [ObjectDetection]
- left: ObjectDetection
right: [PersonReidentification]
- left: PersonReidentification
right: [ImageWindow, RViz, RosTopic]

OpenvinoCommon:

0 comments on commit 1fd9dd4

Please sign in to comment.