ROS package for Coral Edge TPU USB Accelerator
- Ubuntu 16.04 + Kinetic
- Ubuntu 18.04 + Melodic
If you want to run this on Ubuntu 14.04 + Indigo, please see indigo branch.
If you want to run this on PR2, please see pr2 branch.
We need python3.5
or python3.6
to run this package.
Object detector: edgetpu_object_detector.py
Face detector: edgetpu_face_detector.py
Human Pose Estimator: edgetpu_human_pose_estimator.py
For more detailed information, see here.
Follow this page.
echo "deb https://packages.cloud.google.com/apt coral-edgetpu-stable main" | sudo tee /etc/apt/sources.list.d/coral-edgetpu.list
curl https://packages.cloud.google.com/apt/doc/apt-key.gpg | sudo apt-key add -
sudo apt-get update
# If you do not have USB3, install libedgetpu1-std
sudo apt-get install libedgetpu1-max
sudo apt-get install python3-edgetpu
sudo apt-get install python3-pip
wget https://dl.google.com/coral/python/tflite_runtime-1.14.0-cp35-cp35m-linux_x86_64.whl
pip3 install tflite_runtime-1.14.0-cp35-cp35m-linux_x86_64.whl
sudo apt-get install python3-pip
wget https://dl.google.com/coral/python/tflite_runtime-1.14.0-cp36-cp36m-linux_x86_64.whl
pip3 install tflite_runtime-1.14.0-cp36-cp36m-linux_x86_64.whl
source /opt/ros/kinetic/setup.bash
mkdir -p ~/coral_ws/src
cd ~/coral_ws/src
git clone https://github.com/knorth55/coral_usb_ros.git
wstool init
wstool merge coral_usb_ros/fc.rosinstall
wstool update
rosdep install --from-paths . --ignore-src -y -r
cd ~/coral_ws
catkin init
catkin config -DPYTHON_EXECUTABLE=/usr/bin/python3 -DPYTHON_INCLUDE_DIR=/usr/include/python3.5m -DPYTHON_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.5m.so
catkin build
sudo apt-get install python3-opencv
source /opt/ros/melodic/setup.bash
mkdir -p ~/coral_ws/src
cd ~/coral_ws/src
git clone https://github.com/knorth55/coral_usb_ros.git
wstool init
wstool merge coral_usb_ros/fc.rosinstall.melodic
wstool update
rosdep install --from-paths . --ignore-src -y -r
cd ~/coral_ws
catkin init
catkin config -DPYTHON_EXECUTABLE=/usr/bin/python3 -DPYTHON_INCLUDE_DIR=/usr/include/python3.6m -DPYTHON_LIBRARY=/usr/lib/x86_64-linux-gnu/libpython3.6m.so
catkin build
source ~/coral_ws/devel/setup.bash
roscd coral_usb/scripts
rosrun coral_usb download_models.py
# source normal workspace, not edge tpu workspace
# /opt/ros/kinetic/setup.bash or /opt/ros/melodic/setup.bash
source /opt/ros/kinetic/setup.bash
rosrun jsk_perception image_publisher.py _file_name:=$(rospack find jsk_perception)/sample/object_detection_example_1.jpg
# source edge tpu workspace
source ~/coral_ws/devel/setup.bash
# object detector
roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/image_publisher/output
# face detector
roslaunch coral_usb edgetpu_face_detector.launch INPUT_IMAGE:=/image_publisher/output
# human pose estimator
roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/image_publisher/output
# source normal workspace, not edge tpu workspace
# /opt/ros/kinetic/setup.bash or /opt/ros/melodic/setup.bash
source /opt/ros/kinetic/setup.bash
# object detector
rosrun image_view image_view image:=/edgetpu_object_detector/output/image
# face detector
rosrun image_view image_view image:=/edgetpu_face_detector/output/image
# human pose estimator
rosrun image_view image_view image:=/edgetpu_human_pose_estimator/output/image
-
~input/image
(sensor_msgs/Image
)- Input image
-
~output/rects
(jsk_recognition_msgs/RectArray
)- Rectangles of detected objects
-
~output/class
(jsk_recognition_msgs/ClassificationResult
)- Classification results of detected objects
-
~output/image
(sensor_msgs/Image
)- Visualization of detection results
-
~classifier_name
(String
, default:rospy.get_name()
)- Classifier name
-
~model_file
(String
, default:$(rospack find coral_usb)/models/mobilenet_ssd_v2_coco_quant_postprocess_edgetpu.tflite
)- Model file path
-
~label_file
(String
, default:$(rospack find coral_usb)/models/coco_labels.txt
)- Label file path.
-
~score_thresh
: (Float
, default:0.6
)- Score threshold for object detection
-
~top_k
: (Int
, default:100
)- Maximum number of detected objects
-
~input/image
(sensor_msgs/Image
)- Input image
-
~output/rects
(jsk_recognition_msgs/RectArray
)- Rectangles of detected faces
-
~output/class
(jsk_recognition_msgs/ClassificationResult
)- Classification results of detected faces
-
~output/image
(sensor_msgs/Image
)- Visualization of detection results
-
~classifier_name
(String
, default:rospy.get_name()
)- Classifier name
-
~model_file
(String
, default:$(rospack find coral_usb)/models/mobilenet_ssd_v2_face_quant_postprocess_edgetpu.tflite
)- Model file path
-
~score_thresh
: (Float
, default:0.6
)- Score threshold for face detection
-
~top_k
: (Int
, default:100
)- Maximum number of detected faces
Subscribing Topic
-
~input/image
(sensor_msgs/Image
)- Input image
-
~output/poses
(jsk_recognition_msgs/PeoplePoseArray
)- Estimated human poses
-
~output/image
(sensor_msgs/Image
)- Visualization of estimation results
-
~classifier_name
(String
, default:rospy.get_name()
)- Classifier name
-
~model_file
(String
, default:$(rospack find coral_usb)/python/coral_usb/posenet/models/posenet_mobilenet_v1_075_481_641_quant_decoder_edgetpu.tflite
)- Model file path
-
~score_thresh
: (Float
, default:0.2
)- Score threshold for human pose estimation
-
~joint_score_thresh
: (Float
, default:0.2
)- Score threshold of each joint for human pose estimation