summarylogtreecommitdiffstats
diff options
context:
space:
mode:
authorHamish Farrant2020-09-08 07:53:36 +1000
committerHamish Farrant2020-09-08 07:54:38 +1000
commit048a69691b34fce837cda7342facd2dddb4b59af (patch)
treee4e95c94eb8db413b5e8ae53d603b916d30c7042
parent012c65776f92fed7b9dd2f3be4b0cb9c49483743 (diff)
downloadaur-048a69691b34fce837cda7342facd2dddb4b59af.tar.gz
updated to work with noetic and OpenCv 4
-rw-r--r--.SRCINFO45
-rw-r--r--PKGBUILD59
-rw-r--r--fix_cv3_to_4.patch109
3 files changed, 161 insertions, 52 deletions
diff --git a/.SRCINFO b/.SRCINFO
index aedcedd98401..e5cebd2b0e6c 100644
--- a/.SRCINFO
+++ b/.SRCINFO
@@ -1,4 +1,4 @@
-pkgbase = ros-jade-kinect2-calibration
+pkgbase = ros-noetic-kinect2-calibration
pkgdesc = Calibration tool for Kinect One (Kinect v2) in ROS.
pkgver = 0.0.1
pkgrel = 1
@@ -7,27 +7,28 @@ pkgbase = ros-jade-kinect2-calibration
license = apache
makedepends = cmake
makedepends = ros-build-tools
- makedepends = ros-jade-roscpp
- makedepends = ros-jade-rostime
- makedepends = ros-jade-std-msgs
- makedepends = ros-jade-sensor-msgs
- makedepends = ros-jade-message-filters
- makedepends = ros-jade-image-transport
- makedepends = ros-jade-compressed-depth-image-transport
- makedepends = ros-jade-compressed-image-transport
- makedepends = ros-jade-kinect2-bridge
- depends = ros-jade-message-runtime
- depends = ros-jade-roscpp
- depends = ros-jade-rostime
- depends = ros-jade-std-msgs
- depends = ros-jade-sensor-msgs
- depends = ros-jade-message-filters
- depends = ros-jade-image-transport
- depends = ros-jade-compressed-depth-image-transport
- depends = ros-jade-compressed-image-transport
- depends = ros-jade-kinect2-bridge
- source = ros-jade-kinect2-calibration::git+https://github.com/code-iai/iai_kinect2.git
+ makedepends = ros-noetic-roscpp
+ makedepends = ros-noetic-rostime
+ makedepends = ros-noetic-std-msgs
+ makedepends = ros-noetic-sensor-msgs
+ makedepends = ros-noetic-message-filters
+ makedepends = ros-noetic-image-transport
+ makedepends = ros-noetic-compressed-depth-image-transport
+ makedepends = ros-noetic-compressed-image-transport
+ makedepends = ros-noetic-kinect2-bridge
+ depends = ros-noetic-message-runtime
+ depends = ros-noetic-roscpp
+ depends = ros-noetic-rostime
+ depends = ros-noetic-std-msgs
+ depends = ros-noetic-sensor-msgs
+ depends = ros-noetic-message-filters
+ depends = ros-noetic-image-transport
+ depends = ros-noetic-compressed-depth-image-transport
+ depends = ros-noetic-compressed-image-transport
+ depends = ros-noetic-kinect2-bridge
+ source = ros-noetic-kinect2-calibration::git+https://github.com/code-iai/iai_kinect2.git
+ source = fix_cv3_to_4.patch
sha256sums = SKIP
-pkgname = ros-jade-kinect2-calibration
+pkgname = ros-noetic-kinect2-calibration
diff --git a/PKGBUILD b/PKGBUILD
index a16aacb6663d..dff18b5e9688 100644
--- a/PKGBUILD
+++ b/PKGBUILD
@@ -1,7 +1,7 @@
pkgdesc="Calibration tool for Kinect One (Kinect v2) in ROS."
url='https://github.com/code-iai/iai_kinect2'
-pkgname='ros-jade-kinect2-calibration'
+pkgname='ros-noetic-kinect2-calibration'
pkgver='0.0.1'
_pkgver_patch=0
arch=('any')
@@ -10,55 +10,54 @@ license=('apache')
submodule_name=kinect2_calibration
-ros_makedepends=(ros-jade-roscpp
- ros-jade-rostime
- ros-jade-std-msgs
- ros-jade-sensor-msgs
- ros-jade-message-filters
- ros-jade-image-transport
- ros-jade-compressed-depth-image-transport
- ros-jade-compressed-image-transport
- ros-jade-kinect2-bridge)
+ros_makedepends=(ros-noetic-roscpp
+ ros-noetic-rostime
+ ros-noetic-std-msgs
+ ros-noetic-sensor-msgs
+ ros-noetic-message-filters
+ ros-noetic-image-transport
+ ros-noetic-compressed-depth-image-transport
+ ros-noetic-compressed-image-transport
+ ros-noetic-kinect2-bridge)
makedepends=('cmake' 'ros-build-tools'
${ros_makedepends[@]})
-ros_depends=(ros-jade-message-runtime
- ros-jade-roscpp
- ros-jade-rostime
- ros-jade-std-msgs
- ros-jade-sensor-msgs
- ros-jade-message-filters
- ros-jade-image-transport
- ros-jade-compressed-depth-image-transport
- ros-jade-compressed-image-transport
- ros-jade-kinect2-bridge)
+ros_depends=(ros-noetic-message-runtime
+ ros-noetic-roscpp
+ ros-noetic-rostime
+ ros-noetic-std-msgs
+ ros-noetic-sensor-msgs
+ ros-noetic-message-filters
+ ros-noetic-image-transport
+ ros-noetic-compressed-depth-image-transport
+ ros-noetic-compressed-image-transport
+ ros-noetic-kinect2-bridge)
depends=(${ros_depends[@]})
# Git version (e.g. for debugging)
_dir=${pkgname}
-source=("${_dir}"::"git+https://github.com/code-iai/iai_kinect2.git")
+source=("${_dir}"::"git+https://github.com/code-iai/iai_kinect2.git" "fix_cv3_to_4.patch")
sha256sums=('SKIP')
build() {
# Use ROS environment variables
source /usr/share/ros-build-tools/clear-ros-env.sh
- [ -f /opt/ros/jade/setup.bash ] && source /opt/ros/jade/setup.bash
-
+ [ -f /opt/ros/noetic/setup.bash ] && source /opt/ros/noetic/setup.bash
+ cd ros-noetic-kinect2-calibration
+
+ find kinect2_calibration -type f -print0 | xargs -0 dos2unix --
+
+ patch -Np1 -i "${srcdir}/fix_cv3_to_4.patch"
# Create build directory
[ -d ${srcdir}/build ] || mkdir ${srcdir}/build
cd ${srcdir}/build
- # Fix Python2/Python3 conflicts
- /usr/share/ros-build-tools/fix-python-scripts.sh -v 2 ${srcdir}/${_dir}
cmake ${srcdir}/${_dir}/${submodule_name} \
-DCMAKE_BUILD_TYPE=Release \
-DCATKIN_BUILD_BINARY_PACKAGE=ON \
- -DCMAKE_INSTALL_PREFIX=/opt/ros/jade \
- -DPYTHON_EXECUTABLE=/usr/bin/python2 \
- -DPYTHON_INCLUDE_DIR=/usr/include/python2.7 \
- -DPYTHON_LIBRARY=/usr/lib/libpython2.7.so \
- -DPYTHON_BASENAME=-python2.7 \
+ -DCMAKE_INSTALL_PREFIX=/opt/ros/noetic \
+ -DPYTHON_EXECUTABLE=/usr/bin/python \
-DSETUPTOOLS_DEB_LAYOUT=OFF
make
}
diff --git a/fix_cv3_to_4.patch b/fix_cv3_to_4.patch
new file mode 100644
index 000000000000..c201eeaa46c0
--- /dev/null
+++ b/fix_cv3_to_4.patch
@@ -0,0 +1,109 @@
+diff --git a/kinect2_calibration/CMakeLists.txt b/kinect2_calibration/CMakeLists.txt
+index 0ef4dcc..bd0fa4a 100644
+--- a/kinect2_calibration/CMakeLists.txt
++++ b/kinect2_calibration/CMakeLists.txt
+@@ -88,11 +88,10 @@ target_link_libraries(kinect2_calibration
+ # )
+
+ ## Mark executables and/or libraries for installation
+-# install(TARGETS kinect2_bridge kinect2_bridge_node
+-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+-# )
++install(TARGETS kinect2_calibration kinect2_calibration
++ RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
++
++)
+
+ ## Mark cpp header files for installation
+ # install(DIRECTORY include/${PROJECT_NAME}/
+diff --git a/kinect2_calibration/src/kinect2_calibration.cpp b/kinect2_calibration/src/kinect2_calibration.cpp
+index 73d7957..8e35314 100644
+--- a/kinect2_calibration/src/kinect2_calibration.cpp
++++ b/kinect2_calibration/src/kinect2_calibration.cpp
+@@ -110,7 +110,7 @@ public:
+ circleFlags = cv::CALIB_CB_ASYMMETRIC_GRID + cv::CALIB_CB_CLUSTERING;
+ }
+
+- params.push_back(CV_IMWRITE_PNG_COMPRESSION);
++ params.push_back(cv::IMWRITE_PNG_COMPRESSION);
+ params.push_back(9);
+
+ board.resize(boardDims.width * boardDims.height);
+@@ -347,14 +347,14 @@ private:
+
+ if(mode == COLOR || mode == SYNC)
+ {
+- cv::cvtColor(color, colorDisp, CV_GRAY2BGR);
++ cv::cvtColor(color, colorDisp, cv::COLOR_GRAY2BGR);
+ cv::drawChessboardCorners(colorDisp, boardDims, pointsColor, foundColor);
+ //cv::resize(colorDisp, colorDisp, cv::Size(), 0.5, 0.5);
+ //cv::flip(colorDisp, colorDisp, 1);
+ }
+ if(mode == IR || mode == SYNC)
+ {
+- cv::cvtColor(irGrey, irDisp, CV_GRAY2BGR);
++ cv::cvtColor(irGrey, irDisp, cv::COLOR_GRAY2BGR);
+ cv::drawChessboardCorners(irDisp, boardDims, pointsIr, foundIr);
+ //cv::resize(irDisp, irDisp, cv::Size(), 0.5, 0.5);
+ //cv::flip(irDisp, irDisp, 1);
+@@ -746,6 +746,10 @@ private:
+ #elif CV_MAJOR_VERSION == 3
+ error = cv::stereoCalibrate(pointsBoard, pointsIr, pointsColor, cameraMatrixIr, distortionIr, cameraMatrixColor, distortionColor, sizeColor,
+ rotation, translation, essential, fundamental, cv::CALIB_FIX_INTRINSIC, termCriteria);
++
++#elif CV_MAJOR_VERSION == 4
++ 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);
+
+@@ -997,7 +1001,7 @@ public:
+ }
+
+ private:
+- void compareDists(const std::vector<double> &imageDists, const std::vector<double> &depthDists) const
++void compareDists(const std::vector<double> &imageDists, const std::vector<double> &depthDists) const
+ {
+ if(imageDists.size() != depthDists.size())
+ {
+@@ -1043,6 +1047,8 @@ private:
+
+ void computePointDists(const cv::Mat &normal, const double distance, const cv::Mat &region, const cv::Rect &roi, std::vector<double> &depthDists, std::vector<double> &imageDists)
+ {
++
++ OUT_INFO( "rows:" << region.rows<<std::endl);
+ for(int r = 0; r < region.rows; ++r)
+ {
+ const uint16_t *itD = region.ptr<uint16_t>(r);
+@@ -1051,6 +1057,7 @@ private:
+ for(int c = 0; c < region.cols; ++c, ++itD, ++p.x)
+ {
+ const double dDist = *itD / 1000.0;
++ OUT_INFO( "dDist:" << dDist<<std::endl);
+
+ if(dDist < 0.1)
+ {
+@@ -1059,6 +1066,7 @@ private:
+
+ const double iDist = computeDistance(p, normal, distance);
+ const double diff = iDist - dDist;
++ OUT_INFO( "std::abs(diff) :" << std::abs(diff) <<std::endl);
+
+ if(std::abs(diff) > 0.08)
+ {
+@@ -1088,11 +1096,12 @@ private:
+ void getPlane(const size_t index, cv::Mat &normal, double &distance) const
+ {
+ cv::Mat rvec, rotation, translation;
+- //cv::solvePnP(board, points[index], cameraMatrix, distortion, rvec, translation, false, cv::EPNP);
+ #if CV_MAJOR_VERSION == 2
+ cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, board.size(), cv::noArray(), cv::ITERATIVE);
+ #elif CV_MAJOR_VERSION == 3
+ cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, 0.99, cv::noArray(), cv::SOLVEPNP_ITERATIVE);
++#elif CV_MAJOR_VERSION == 4
++ cv::solvePnPRansac(board, points[index], cameraMatrix, distortion, rvec, translation, false, 300, 0.05, 0.99, cv::noArray(), cv::SOLVEPNP_ITERATIVE);
+ #endif
+ cv::Rodrigues(rvec, rotation);
+