Skip to content

Commit

Permalink
Merge pull request #51 from RachelRen05/support_oa
Browse files Browse the repository at this point in the history
Support oa
  • Loading branch information
LewisLiuPub authored Jan 28, 2019
2 parents 1ff9c60 + d6837fb commit 5d5c319
Show file tree
Hide file tree
Showing 6 changed files with 144 additions and 1 deletion.
6 changes: 5 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ Currently, the inference feature list is supported:
### Topic
#### Subscribed Topic
- Image topic:
```/camera/color/image_raw```([sensor_msgs::msg::Image](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Image.msg))
```/openvino_toolkit/image_raw```([sensor_msgs::msg::Image](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Image.msg))
#### Published Topic
- Face Detection:
```/ros2_openvino_toolkit/face_detection```([object_msgs:msg:ObjectsInBoxes](https://github.com/intel/ros2_object_msgs/blob/master/msg/ObjectsInBoxes.msg))
Expand Down Expand Up @@ -168,6 +168,10 @@ One-step installation scripts are provided for the dependencies' installation. P
```bash
ros2 launch dynamic_vino_sample pipeline_object_oss.launch.py
```
* run object detection sample code input from RealSenseCameraTopic.
```bash
ros2 launch dynamic_vino_sample pipeline_object_oss_topic.launch.py
```
* run object segmentation sample code input from RealSenseCameraTopic.
```bash
ros2 launch dynamic_vino_sample pipeline_segmentation.launch.py
Expand Down
4 changes: 4 additions & 0 deletions doc/BINARY_VERSION_README.md
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,10 @@ This project is a ROS2 wrapper for CV API of [OpenVINO™](https://software.inte
```bash
ros2 launch dynamic_vino_sample pipeline_object.launch.py
```
* run object detection sample code input from RealSenseCameraTopic.
```bash
ros2 launch dynamic_vino_sample pipeline_object_topic.launch.py
```
* run object segmentation sample code input from RealSenseCameraTopic.
```bash
ros2 launch dynamic_vino_sample pipeline_segmentation.launch.py
Expand Down
45 changes: 45 additions & 0 deletions sample/launch/pipeline_object_oss_topic.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
# 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_object_oss_topic.yaml');
default_rviz = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'launch', 'rviz/default.rviz');
return LaunchDescription([
# Realsense
launch_ros.actions.Node(
package='realsense_ros2_camera', node_executable='realsense_ros2_camera',output='screen'),
# Openvino Detection
launch_ros.actions.Node(
package='dynamic_vino_sample', node_executable='pipeline_with_params',
arguments=['-config', default_yaml],
remappings=[
('/openvino_toolkit/image_raw', '/camera/color/image_raw'),
('/openvino_toolkit/detected_objects', '/ros2_openvino_toolkit/detected_objects'),
('/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]),
])
46 changes: 46 additions & 0 deletions sample/launch/pipeline_object_topic.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
# 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_object_topic.yaml');
default_rviz = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'launch', 'rviz/default.rviz');
return LaunchDescription([
#realsense
launch_ros.actions.Node(
package='realsense_ros2_camera', node_executable='realsense_ros2_camera',output='screen'),

#openvino detection
launch_ros.actions.Node(
package='dynamic_vino_sample', node_executable='pipeline_with_params',
arguments=['-config', default_yaml],
remappings=[
('/openvino_toolkit/image_raw', '/camera/color/image_raw'),
('/openvino_toolkit/detected_objects', '/ros2_openvino_toolkit/detected_objects'),
('/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]),
])
22 changes: 22 additions & 0 deletions sample/param/pipeline_object_oss_topic.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
Pipelines:
- name: object
inputs: [RealSenseCameraTopic]
infers:
- name: ObjectDetection
model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml
engine: CPU
label: to/be/set/xxx.labels
batch: 16
outputs: [ImageWindow, RosTopic, RViz]
confidence_threshold: 0.2
connects:
- left: RealSenseCameraTopic
right: [ObjectDetection]
- left: ObjectDetection
right: [ImageWindow]
- left: ObjectDetection
right: [RosTopic]
- left: ObjectDetection
right: [RViz]

OpenvinoCommon:
22 changes: 22 additions & 0 deletions sample/param/pipeline_object_topic.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
Pipelines:
- name: object
inputs: [RealSenseCameraTopic]
infers:
- name: ObjectDetection
model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/person-vehicle-bike-detection-crossroad-0078/FP32/person-vehicle-bike-detection-crossroad-0078.xml
engine: CPU
label: to/be/set/xxx.labels
batch: 16
outputs: [ImageWindow, RosTopic, RViz]
confidence_threshold: 0.2
connects:
- left: RealSenseCameraTopic
right: [ObjectDetection]
- left: ObjectDetection
right: [ImageWindow]
- left: ObjectDetection
right: [RosTopic]
- left: ObjectDetection
right: [RViz]

OpenvinoCommon:

0 comments on commit 5d5c319

Please sign in to comment.