Repository Summary
Checkout URI | https://github.com/intel/ros2_object_analytics.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2019-09-16 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
object_analytics_msgs | 0.5.4 |
object_analytics_node | 0.5.4 |
object_analytics_rviz | 0.5.4 |
README
ros2_object_analytics
Object Analytics (OA) is ROS2 module for Realtime object tracking and 3D localization. These packages aim to provide real-time object analyses over RGB-D camera inputs, enabling ROS developer to easily create amazing robotics advanced features, like intelligent collision avoidance, people follow and semantic SLAM. It consumes sensor_msgs::PointClould2 data delivered by RGB-D camera, subscribes topic on object detection by ros2_intel_movidius_ncs, publishes topics on object tracking in 2D RGB image and object localization in 3D camera coordination system.
OA keeps integrating with various “state-of-the-art” algorithms.
- Object detection offload to VPU, Intel Movidius NCS, with MobileNet SSD model and Caffe framework(TODO).
System Requirements
We support Ubuntu Linux Bionic Beaver 18.04 on 64-bit. We not support Mac OS X and Windows.
Hardware Requirements
- Intel NUC (CPU: Intel i7-6700HQ @2.60GHz, Mem:16G)
- Intel Movidius Neural Compute Stick
- Intel RealSense D435i/D435/D415
Dependencies
Install ROS2 desktop packages ros-dashing-desktop
sudo apt-get install ros-dashing-desktop #Follow instructions above in the ROS docs if this doesn't work
The ros-dashing-desktop will include below packages.
- ament_cmake
- std_msgs
- sensor_msgs
- geometry_msgs
- rclcpp
- rosidl_default_generators
- rosidl_interface_packages
- launch
- ros2run
- class_loader
- pcl_conversions
Install ROS2 dependences
sudo apt-get install ros-dashing-cv-bridge ros-dashing-object-msgs ros-dashing-image-transport ros-dashing-librealsense2 ros-dashing-realsense-camera-msgs ros-dashing-realsense-ros2-camera
- cv_bridge
- object_msgs
- ros2_message_filters
- ros2_intel_realsense (The only supported RGB-D camera by now is Intel RealSense)
Install ros2_intel_movidius
ros2_intel_movidius has not integrated in ROS2 release, so there is no debian package available for Movidius NCS installation, need to build from source, and it should be installed before OpenCV3, more details please refer to https://github.com/intel/ros2_intel_movidius_ncs).
# Build ncsdk
mkdir ~/code
cd ~/code
git clone https://github.com/movidius/ncsdk
git clone https://github.com/movidius/ncappzoo
cd ~/code/ncsdk
make install
ln -sf ~/code/ncappzoo /opt/movidius/ncappzoo
# Build ros2_intel_movidius_ncs
mkdir ~/ros2_ws/src -p
cd ~/ros2_ws/src
git clone https://github.com/intel/ros2_intel_movidius_ncs.git
cd ~/ros2_ws
source /opt/ros/dashing/setup.bash
colcon build --symlink-install (Install python3-colcon-common-extensions by apt-get if colcon command not exist)
# Build CNN model (Please plugin NCS device on the host while compiling)
cd /opt/movidius/ncappzoo/caffe/SSD_MobileNet
make
# Copy object label file to NCSDK installation location.
cp ~/ros2_ws/src/ros2_intel_movidius_ncs/data/labels/* /opt/movidius/ncappzoo/data/ilsvrc12/
Build OpenCV3
OpenCV3 & Opencv-Contrib 3.3 (OA depends on tracking feature from OpenCV Contrib 3.3. OpenCV 3.3 is not integrated in ROS2 Dashing release, need to build and install Opencv3 with Opencv-Contrib from source to apply tracking feature)
# Build and Install OpenCV3 with Opencv-Contrib
mkdir ${HOME}/opencv
cd ${HOME}/opencv
git clone https://github.com/opencv/opencv.git -b 3.3.0
git clone https://github.com/opencv/opencv_contrib.git -b 3.3.0
mkdir opencv/build -p
cd opencv/build
cmake -DOPENCV_EXTRA_MODULES_PATH=${HOME}/opencv/opencv_contrib/modules \
-DCMAKE_INSTALL_PREFIX=/usr/local -DBUILD_opencv_cnn_3dobj=OFF ..
make -j8
sudo make install
sudo ldconfig
Install OpenCV3 dependences
sudo apt-get install liblz4-dev
Install OA
Install OA debian packages
File truncated at 100 lines see the full file
CONTRIBUTING
Repository Summary
Checkout URI | https://github.com/intel/ros2_object_analytics.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2019-09-16 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
object_analytics_msgs | 0.5.4 |
object_analytics_node | 0.5.4 |
object_analytics_rviz | 0.5.4 |
README
ros2_object_analytics
Object Analytics (OA) is ROS2 module for Realtime object tracking and 3D localization. These packages aim to provide real-time object analyses over RGB-D camera inputs, enabling ROS developer to easily create amazing robotics advanced features, like intelligent collision avoidance, people follow and semantic SLAM. It consumes sensor_msgs::PointClould2 data delivered by RGB-D camera, subscribes topic on object detection by ros2_intel_movidius_ncs, publishes topics on object tracking in 2D RGB image and object localization in 3D camera coordination system.
OA keeps integrating with various “state-of-the-art” algorithms.
- Object detection offload to VPU, Intel Movidius NCS, with MobileNet SSD model and Caffe framework(TODO).
System Requirements
We support Ubuntu Linux Bionic Beaver 18.04 on 64-bit. We not support Mac OS X and Windows.
Hardware Requirements
- Intel NUC (CPU: Intel i7-6700HQ @2.60GHz, Mem:16G)
- Intel Movidius Neural Compute Stick
- Intel RealSense D435i/D435/D415
Dependencies
Install ROS2 desktop packages ros-dashing-desktop
sudo apt-get install ros-dashing-desktop #Follow instructions above in the ROS docs if this doesn't work
The ros-dashing-desktop will include below packages.
- ament_cmake
- std_msgs
- sensor_msgs
- geometry_msgs
- rclcpp
- rosidl_default_generators
- rosidl_interface_packages
- launch
- ros2run
- class_loader
- pcl_conversions
Install ROS2 dependences
sudo apt-get install ros-dashing-cv-bridge ros-dashing-object-msgs ros-dashing-image-transport ros-dashing-librealsense2 ros-dashing-realsense-camera-msgs ros-dashing-realsense-ros2-camera
- cv_bridge
- object_msgs
- ros2_message_filters
- ros2_intel_realsense (The only supported RGB-D camera by now is Intel RealSense)
Install ros2_intel_movidius
ros2_intel_movidius has not integrated in ROS2 release, so there is no debian package available for Movidius NCS installation, need to build from source, and it should be installed before OpenCV3, more details please refer to https://github.com/intel/ros2_intel_movidius_ncs).
# Build ncsdk
mkdir ~/code
cd ~/code
git clone https://github.com/movidius/ncsdk
git clone https://github.com/movidius/ncappzoo
cd ~/code/ncsdk
make install
ln -sf ~/code/ncappzoo /opt/movidius/ncappzoo
# Build ros2_intel_movidius_ncs
mkdir ~/ros2_ws/src -p
cd ~/ros2_ws/src
git clone https://github.com/intel/ros2_intel_movidius_ncs.git
cd ~/ros2_ws
source /opt/ros/dashing/setup.bash
colcon build --symlink-install (Install python3-colcon-common-extensions by apt-get if colcon command not exist)
# Build CNN model (Please plugin NCS device on the host while compiling)
cd /opt/movidius/ncappzoo/caffe/SSD_MobileNet
make
# Copy object label file to NCSDK installation location.
cp ~/ros2_ws/src/ros2_intel_movidius_ncs/data/labels/* /opt/movidius/ncappzoo/data/ilsvrc12/
Build OpenCV3
OpenCV3 & Opencv-Contrib 3.3 (OA depends on tracking feature from OpenCV Contrib 3.3. OpenCV 3.3 is not integrated in ROS2 Dashing release, need to build and install Opencv3 with Opencv-Contrib from source to apply tracking feature)
# Build and Install OpenCV3 with Opencv-Contrib
mkdir ${HOME}/opencv
cd ${HOME}/opencv
git clone https://github.com/opencv/opencv.git -b 3.3.0
git clone https://github.com/opencv/opencv_contrib.git -b 3.3.0
mkdir opencv/build -p
cd opencv/build
cmake -DOPENCV_EXTRA_MODULES_PATH=${HOME}/opencv/opencv_contrib/modules \
-DCMAKE_INSTALL_PREFIX=/usr/local -DBUILD_opencv_cnn_3dobj=OFF ..
make -j8
sudo make install
sudo ldconfig
Install OpenCV3 dependences
sudo apt-get install liblz4-dev
Install OA
Install OA debian packages
File truncated at 100 lines see the full file