VIPER Core is the base functionality that comes with each instance. ROS API is used to communicate with the device.
VIPER Core consists of the following features.
Note
All topics are provided without a namespace. When you are using your VIPER, please take its namespace into account.
VIPER has a set of two cameras. Images come in several formats:
rviz and rqt can be used to view images.
rosrun image_view image_view image:=/image_raw
The following sample will allow you to stream images from your VIPER and display them using OpenCV library.
First you need to create a catkin workspace.
source /opt/ros/kinetic/setup.bash
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
Then create a simple package using the following files.
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>
void imageCallback(const sensor_msgs::ImageConstPtr& msg)
{
try
{
cv::imshow("Image view", cv_bridge::toCvShare(msg, "rgb8")->image);
cv::waitKey(30);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("Could not convert from '%s' to 'rgb8'.", msg->encoding.c_str());
}
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "image_streaming");
ros::NodeHandle nh;
cv::namedWindow("Image view");
cv::startWindowThread();
image_transport::ImageTransport it(nh);
image_transport::Subscriber sub = it.subscribe("image_raw", 1, imageCallback);
ros::spin();
cv::destroyWindow("Image view");
}
image_streaming/CMakeLists.txt
cmake_minimum_required(VERSION 3.5.1)
project(image_streaming)
add_compile_options(-std=c++14 -O3)
# Find required packages
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
sensor_msgs
cv_bridge
image_transport
)
find_package(OpenCV REQUIRED)
catkin_package(
LIBRARIES
)
include_directories(
include
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
add_executable(image_streaming main.cpp)
target_link_libraries(image_streaming ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})
<?xml version="1.0"?>
<package format="2">
<name>image_streaming</name>
<version>1.0.0</version>
<description>Sample image streaming application</description>
<maintainer email="arnas.ivanavicius@rubedos.com">Arnas Ivanavicius</maintainer>
<author email="arnas.ivanavicius@rubedos.com">Arnas Ivanavicius</author>
<license>Proprietary</license>
<url type="website">http://www.rubedos.com</url>
<buildtool_depend>catkin</buildtool_depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>cv_bridge</depend>
<depend>image_transport</depend>
</package>
Build and run the sample:
cd ~/catkin_ws
catkin build image_streaming
source devel/setup.bash
export ROS_MASTER_URI=http://<VIPER_IP>:11311
rosrun image_streaming image_streaming
You should see image_raw
topic being published to the Image view
window.
Please refer to ROS API to see the full list of topics.
Disparity image is an image that contains a shift value for each pixel in the left rectified image with respect to the right rectified image of the same scene, while both images have been taken at the same time.
image_view package can be used to view disparity images.
rosrun image_view disparity_view image:=/disparity
The following sample will allow you to stream disparity map from your VIPER. It converts disparity image which is float type to grayscale image using OpenCV library.
First you need to create a catkin workspace.
source /opt/ros/kinetic/setup.bash
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
Then create a simple package using the following files.
#include <ros/ros.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>
#include <stereo_msgs/DisparityImage.h>
void disparityImageCallback(const stereo_msgs::DisparityImageConstPtr& msg)
{
// Extracting disparity image
const sensor_msgs::Image& dimage = msg->image;
const cv::Mat_<float> dmat(dimage.height, dimage.width, (float*)&dimage.data[0], dimage.step);
cv::Mat disp_u(dmat.size(), 0);
// Converts disparity to uint8
dmat.convertTo(disp_u, disp_u.type());
cv::imshow("Disparity view", disp_u);
cv::waitKey(30);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "disparity_streaming");
ros::NodeHandle nh;
cv::namedWindow("Disparity view");
cv::startWindowThread();
ros::Subscriber sub = nh.subscribe("disparity", 1, disparityImageCallback);
ros::spin();
cv::destroyWindow("Disparity view");
}
disparity_streaming/CMakeLists.txt
cmake_minimum_required(VERSION 3.5.1)
project(disparity_streaming)
add_compile_options(-std=c++14 -O3)
# Find required packages
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
sensor_msgs
cv_bridge
stereo_msgs
)
find_package(OpenCV REQUIRED)
catkin_package(
LIBRARIES
)
include_directories(
include
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
add_executable(disparity_streaming main.cpp)
target_link_libraries(disparity_streaming ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})
disparity_streaming/package.xml
<?xml version="1.0"?>
<package format="2">
<name>disparity_streaming</name>
<version>1.0.0</version>
<description>Simple disparity streaming application</description>
<maintainer email="arnas.ivanavicius@rubedos.com">Arnas Ivanavicius</maintainer>
<author email="arnas.ivanavicius@rubedos.com">Arnas Ivanavicius</author>
<license>Proprietary</license>
<url type="website">http://www.rubedos.com</url>
<buildtool_depend>catkin</buildtool_depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>stereo_msgs</depend>
<depend>cv_bridge</depend>
</package>
Build and run the sample:
cd ~/catkin_ws
catkin build disparity_streaming
source devel/setup.bash
export ROS_MASTER_URI=http://<VIPER_IP>:11311
rosrun disparity_streaming disparity_streaming
You should see disparity
topic being published to the Disparity view
window.
Point cloud is a 3D data structure that contains x, y, z coordinates (in meters) for each pixel in left rectified image, and describes a 3D scene.
rviz can be used to view point clouds.
- run rviz [rosrun rviz rviz];
- Add display type in rviz [Add->PointCloud2];
- Browse for the
points2
topic;- Make sure correct link is selected, e.g.
cvm_base_link
.
The following sample will allow you to stream point clouds from your VIPER. It uses PCL library to visualize point clouds received from VIPER.
First you need to create a catkin workspace.
source /opt/ros/kinetic/setup.bash
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
Then create a simple package using the following files.
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/visualization/cloud_viewer.h>
#include <string>
#include <pcl/filters/passthrough.h>
typedef pcl::PointXYZRGB PointType;
class PointCloudProcessor
{
public:
PointCloudProcessor()
: m_viewer()
, m_buffer()
, m_mutex()
, m_cloudSubscriber()
{
}
void setViewer(boost::shared_ptr<pcl::visualization::CloudViewer>& viewer)
{
m_viewer = viewer;
}
void subscribeTo(const std::string& topicName)
{
ros::NodeHandle nh;
m_cloudSubscriber = nh.subscribe<sensor_msgs::PointCloud2>(topicName, 1, boost::bind(&PointCloudProcessor::cloudCallback, this, _1));
}
private:
void cloudCallback(const sensor_msgs::PointCloud2ConstPtr& msg)
{
pcl::PointCloud<PointType>::Ptr pclCloud(new pcl::PointCloud<PointType>);
pcl::fromROSMsg(*msg, *pclCloud);
pcl::PointCloud<PointType>::Ptr filtered(new pcl::PointCloud<PointType>());
pcl::PassThrough<PointType> pass;
pass.setInputCloud(pclCloud);
pass.setFilterFieldName ("z");
pass.setFilterLimits (0.0, 30); // (min,max)
pass.filter(*filtered);
m_viewer->showCloud(filtered);
}
boost::shared_ptr<pcl::visualization::CloudViewer> m_viewer;
pcl::PointCloud<PointType>::ConstPtr m_buffer;
boost::mutex m_mutex;
ros::Subscriber m_cloudSubscriber;
};
int main(int argc, char** argv)
{
ros::init(argc, argv, "pointcloud_streaming");
PointCloudProcessor v;
boost::shared_ptr<pcl::visualization::CloudViewer> viewer(new pcl::visualization::CloudViewer("PointCloud view"));
v.setViewer(viewer);
v.subscribeTo("points2");
ros::spin();
return 0;
}
pointcloud_streaming/CMakeLists.txt
cmake_minimum_required(VERSION 3.5.1)
project(pointcloud_streaming)
add_compile_options(-std=c++14 -O3)
# Find required packages
find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
pcl_ros
pcl_conversions
)
#find_package(PCL 1.8 REQUIRED)
add_definitions(${PCL_DEFINITIONS})
catkin_package(
LIBRARIES
)
include_directories(
include
${catkin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)
add_executable(pointcloud_streaming main.cpp)
target_link_libraries(pointcloud_streaming ${catkin_LIBRARIES} ${PCL_LIBRARIES})
pointcloud_streaming/package.xml
<?xml version="1.0"?>
<package format="2">
<name>pointcloud_streaming</name>
<version>1.0.0</version>
<description>Simple point cloud streaming application</description>
<maintainer email="arnas.ivanavicius@rubedos.com">Arnas Ivanavicius</maintainer>
<author email="arnas.ivanavicius@rubedos.com">Arnas Ivanavicius</author>
<license>Proprietary</license>
<url type="website">http://www.rubedos.com</url>
<buildtool_depend>catkin</buildtool_depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
<depend>pcl_ros</depend>
<depend>pcl_conversions</depend>
</package>
Build and run the sample:
cd ~/catkin_ws
catkin build pointcloud_streaming
source devel/setup.bash
export ROS_MASTER_URI=http://<VIPER_IP>:11311
rosrun pointcloud_streaming pointcloud_streaming
You should see points2
topic being published to the PointCloud view
window.
Please refer to PCL documentation in order to get familiar with point cloud processing.