Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion kinect2_bridge/src/kinect2_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ class Kinect2Bridge
priv_nh.param("queue_size", queueSize, 2);
priv_nh.param("bilateral_filter", bilateral_filter, true);
priv_nh.param("edge_aware_filter", edge_aware_filter, true);
priv_nh.param("publish_tf", publishTF, false);
priv_nh.param("publish_tf", publishTF, true);
priv_nh.param("base_name_tf", baseNameTF, base_name);
priv_nh.param("worker_threads", worker_threads, 4);

Expand Down
14 changes: 14 additions & 0 deletions kinect2_calibration/src/kinect2_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <sys/stat.h>

#include <opencv2/opencv.hpp>
#include "opencv2/core/version.hpp"

#include <ros/ros.h>
#include <ros/spinner.h>
Expand Down Expand Up @@ -715,9 +716,17 @@ class CameraCalibration
OUT_INFO("Distortion Coeeficients Ir:" << std::endl << distortionIr << std::endl);

OUT_INFO("calibrating Color and Ir extrinsics...");

#if CV_VERSION_EPOCH == 2 || (!defined CV_VERSION_EPOCH && CV_VERSION_MAJOR == 2)
error = cv::stereoCalibrate(pointsBoard, pointsIr, pointsColor, cameraMatrixIr, distortionIr, cameraMatrixColor, distortionColor, sizeColor,
rotation, translation, essential, fundamental, termCriteria,
cv::CALIB_FIX_INTRINSIC);
#elif CV_VERSION_MAJOR == 3
error = cv::stereoCalibrate(pointsBoard, pointsIr, pointsColor, cameraMatrixIr, distortionIr, cameraMatrixColor, distortionColor, sizeColor,
rotation, translation, essential, fundamental,
cv::CALIB_FIX_INTRINSIC,termCriteria);
#endif

OUT_INFO("re-projection error: " << error << std::endl);

OUT_INFO("Rotation:" << std::endl << rotation);
Expand Down Expand Up @@ -1047,7 +1056,12 @@ class DepthCalibration
{
cv::Mat rvec, rotation, translation;
//cv::solvePnP(board, points[index], cameraMatrix, distortion, rvec, translation, false, cv::EPNP);

#if CV_VERSION_EPOCH == 2 || (!defined CV_VERSION_EPOCH && CV_VERSION_MAJOR == 2)
cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, board.size(), cv::noArray(), cv::ITERATIVE);
#elif CV_VERSION_MAJOR == 3
cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, board.size(), cv::noArray(), cv::SOLVEPNP_ITERATIVE);
#endif
cv::Rodrigues(rvec, rotation);

normal = cv::Mat(3, 1, CV_64F);
Expand Down
7 changes: 7 additions & 0 deletions kinect2_registration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,13 @@ find_package(cmake_modules QUIET)

## System dependencies are found with CMake's conventions
find_package(OpenCV REQUIRED)
if(OpenCV_FOUND)
message(STATUS "OpenCV version: ${OpenCV_VERSION}")
if(NOT OpenCV_VERSION VERSION_LESS "3.0.0")
add_definitions(-DHAVE_OPENCV3)
message(STATUS "defined HAVE_OPENCV3")
endif()
endif()
find_package(OpenMP)
find_package(Eigen)
find_package(OpenCL)
Expand Down
6 changes: 5 additions & 1 deletion kinect2_viewer/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,9 @@ This is a simple viewer for the combined color an depth image provided by Kinect

It just listens to two ROS topics and displays a the color with the overlayed colored depth image or a registered point cloud.

Update:
It can disable the visualization and just publish pointcloud2 now with publish_cloud option with changes in lock and unlock to assert that the color corresponded to the depth image in the same timeframe. Change pcl RGBA point cloud to RGB

## Dependencies

- ROS Hydro/Indigo
Expand All @@ -24,8 +27,9 @@ It just listens to two ROS topics and displays a the color with the overlayed co
kinect2_viewer [options]
name: 'any string' equals to the kinect2_bridge topic base name
mode: 'qhd', 'hd', 'sd' or 'ir'
visualization: 'image', 'cloud' or 'both'
visualization: 'none', 'image', 'cloud' or 'both'
options:
'publish_cloud' publish PointXYZRGBA cloud topic
'compressed' use compressed instead of raw topics
'approx' use approximate time synchronization
```
Expand Down
Loading