Show EOL distros:
Package Summary
Released
Documented
DNN based detection
- Maintainer status: developed
- Maintainer: Jim Vaughan <jimv AT mrjim DOT com>, Rohan Agrawal <send2arohan AT gmail DOT com>
- Author: Jim Vaughan <jimv AT mrjim DOT com>
- License: BSD
- Source: git https://github.com/UbiquityRobotics/dnn_detect.git (branch: kinetic-devel)
Package Summary
Released
Documented
DNN based detection
- Maintainer status: maintained
- Maintainer: Jim Vaughan <jimv AT mrjim DOT com>, Rohan Agrawal <send2arohan AT gmail DOT com>
- Author: Jim Vaughan <jimv AT mrjim DOT com>
- License: BSD
- Source: git https://github.com/UbiquityRobotics/dnn_detect.git (branch: kinetic-devel)
Contents
Nodes
dnn_detect
dnn_detect uses the OpenCV Deep Neural Network module to find objects in an image stream and provide their bounding boxes.Subscribed Topics
/camera (sensor_msgs/Image)- The images to be processed.
Published Topics
/dnn_objects (dnn_detect/DetectedObjectArray)- Details of detected objects
- Input image with detected objects outlined
Services
~detect (dnn_detect/Detect)- Trigger a detection when in single-shot mode
Parameters
~single_shot (bool, default: false)- If set, detection is only performed when the detect service is called
- If set, images with objects outlined will be published
- Path to directory containing data
- Name of protonet file, relative to data_dir
- Name of caffe model file, relative to data_dir
- Minimum confidence (0..1) for an object to be included in the results
- size of image (pixels) to operate on
- Scale factor for model - the intensity values in the image are multiplied by this
- Mean value for model - this is subtracted from the intensity values in the image
- Comma delimited list of class names
Installation
sudo apt install ros-kinetic-dnn-detect
Sample Usage
The sample launch file uses chuanqi305's MobileNet-SSD
A camera node, such as usb_cam needs to be running
For example:
rosrun usb_cam usb_cam_node
Then dnn_detect can be launched:
roslaunch dnn_detect dnn_detect.launch camera:=/usb_cam image:=image_raw
and the results viewed with: {{ rqt_image_view /dnn_images or:
rostopic echo /dnn_objects