From 893d2d100fccd2b96f300f675bdb82506faec110 Mon Sep 17 00:00:00 2001 From: JakobEngel Date: Fri, 26 Apr 2013 17:27:44 +0200 Subject: [PATCH 1/8] changes such that make eclipse-project works properly --- ptam/Makefile | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ptam/Makefile b/ptam/Makefile index 24b5bee..82a1b47 100644 --- a/ptam/Makefile +++ b/ptam/Makefile @@ -2,8 +2,10 @@ all: cd thirdparty && make make -f Makefile_ptam +eclipse-project: + make -f Makefile_ptam $@ + .DEFAULT: cd thirdparty && make $@ make -f Makefile_ptam $@ - From 4cdbd9b1ab6b74474f89b49d68700fcc5d85312b Mon Sep 17 00:00:00 2001 From: JakobEngel Date: Fri, 26 Apr 2013 17:33:22 +0200 Subject: [PATCH 2/8] made to work with rgb8 images. no copy-overhead if image already is grayscale. --- ptam/src/System.cc | 28 ++++++++++++++++++++++++---- 1 file changed, 24 insertions(+), 4 deletions(-) diff --git a/ptam/src/System.cc b/ptam/src/System.cc index 10a783a..156f65b 100644 --- a/ptam/src/System.cc +++ b/ptam/src/System.cc @@ -90,9 +90,29 @@ void System::imageCallback(const sensor_msgs::ImageConstPtr & img) { // static ros::Time t = img->header.stamp; - - ROS_ASSERT(img->encoding == sensor_msgs::image_encodings::MONO8 && img->step == img->width); - + // image-stub which will contain bw image + cv::Mat imgBW; + + ROS_ASSERT(img->step == img->width); + + if(img->encoding == sensor_msgs::image_encodings::RGB8) + { + // wrap around color data, and convert to bw image. + cv::Mat imgColTmp = cv::Mat(img->height, img->width,CV_8UC3, (uchar*)img->data.data()); + cv::cvtColor(imgColTmp,imgBW,CV_RGB2GRAY); + } + else if(img->encoding == sensor_msgs::image_encodings::MONO8) + { + // just wrap around data... does not copy any image data. + imgBW = cv::Mat(img->height, img->width,CV_8U, (uchar*)img->data.data()); + } + else + { + // throw error + ROS_ASSERT(img->encoding == sensor_msgs::image_encodings::RGB8 || img->encoding == sensor_msgs::image_encodings::MONO8); + } + + VarParams *varParams = ParamsAccess::varParams; if(first_frame_){ @@ -120,7 +140,7 @@ void System::imageCallback(const sensor_msgs::ImageConstPtr & img) // ------------------- // TODO: avoid copy, but calling TrackFrame, with the ros image, because there is another copy inside TrackFrame - CVD::BasicImage img_tmp((CVD::byte *)&img->data[0], CVD::ImageRef(img->width, img->height)); + CVD::BasicImage img_tmp(imgBW.data, CVD::ImageRef(img->width, img->height)); CVD::copy(img_tmp, img_bw_); bool tracker_draw = false; From 48276f8927f105f70c13aec159940f3eb4ba9bb0 Mon Sep 17 00:00:00 2001 From: JakobEngel Date: Sat, 27 Apr 2013 20:38:26 +0200 Subject: [PATCH 3/8] made calibrator work on rgb data as well. --- ptam/src/CameraCalibrator.cc | 34 ++++++++++++++++++++++++++++------ 1 file changed, 28 insertions(+), 6 deletions(-) diff --git a/ptam/src/CameraCalibrator.cc b/ptam/src/CameraCalibrator.cc index ac6b617..47b46c5 100644 --- a/ptam/src/CameraCalibrator.cc +++ b/ptam/src/CameraCalibrator.cc @@ -15,6 +15,8 @@ #include #include +#include + using namespace CVD; using namespace std; using namespace GVars3; @@ -56,14 +58,34 @@ int main(int argc, char** argv) void CameraCalibrator::imageCallback(const sensor_msgs::ImageConstPtr & img) { - ROS_ASSERT(img->encoding == sensor_msgs::image_encodings::MONO8 && img->step == img->width); + ROS_ASSERT(img->step == img->width); + + cv::Mat imgBW; + if(img->encoding == sensor_msgs::image_encodings::RGB8) + { + // wrap around color data, and convert to bw image. + cv::Mat imgColTmp = cv::Mat(img->height, img->width,CV_8UC3, (uchar*)img->data.data()); + cv::cvtColor(imgColTmp,imgBW,CV_RGB2GRAY); + } + else if(img->encoding == sensor_msgs::image_encodings::MONO8) + { + // just wrap around data... does not copy any image data. + imgBW = cv::Mat(img->height, img->width,CV_8U, (uchar*)img->data.data()); + } + else + { + // throw error + ROS_ASSERT(img->encoding == sensor_msgs::image_encodings::RGB8 || img->encoding == sensor_msgs::image_encodings::MONO8); + } + + // resize internal image if required + if(mCurrentImage.size().x != img->width || mCurrentImage.size().y != img->height) + mCurrentImage.resize(CVD::ImageRef(img->width, img->height)); - CVD::ImageRef size(img->width, img->height); - mCurrentImage.resize(size); + // copy data + memcpy(mCurrentImage.data(),imgBW.data,img->width * img->height); - CVD::BasicImage img_tmp((CVD::byte *)&img->data[0], size); - CVD::copy(img_tmp, mCurrentImage); - mNewImage = true; + mNewImage = true; } CameraCalibrator::CameraCalibrator() : From 77aeae1a095ff723cb17c8fa4718951ed662ed38 Mon Sep 17 00:00:00 2001 From: JakobEngel Date: Sat, 27 Apr 2013 20:40:18 +0200 Subject: [PATCH 4/8] just remove that check and init will work almost always... i dont think the check is really needed for anything. --- ptam/src/MapMaker.cc | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ptam/src/MapMaker.cc b/ptam/src/MapMaker.cc index 47b01e0..3efb5a7 100644 --- a/ptam/src/MapMaker.cc +++ b/ptam/src/MapMaker.cc @@ -452,11 +452,11 @@ bool MapMaker::InitFromStereo(KeyFrame &kF, } //sanity check: if the point variance is too large assume init is crap --> very hacky, assumes flat init scene!! - if((pkFirst->dSceneDepthSigma+pkSecond->dSceneDepthSigma)/2.0>0.5) - { - ROS_WARN_STREAM("Initial map rejected because of too large point variance. Point sigma: " << ((pkFirst->dSceneDepthSigma+pkSecond->dSceneDepthSigma)/2.0)); - return false; - } + //if((pkFirst->dSceneDepthSigma+pkSecond->dSceneDepthSigma)/2.0>0.5) + //{ + // ROS_WARN_STREAM("Initial map rejected because of too large point variance. Point sigma: " << ((pkFirst->dSceneDepthSigma+pkSecond->dSceneDepthSigma)/2.0)); + // return false; + //} //} From 2d72ec39bfa27508cdff085adf381dc412690936 Mon Sep 17 00:00:00 2001 From: JakobEngel Date: Sat, 27 Apr 2013 20:44:21 +0200 Subject: [PATCH 5/8] added cam parameter output (once on init) --- ptam/src/ATANCamera.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ptam/src/ATANCamera.cc b/ptam/src/ATANCamera.cc index 185cef1..39d8f8c 100644 --- a/ptam/src/ATANCamera.cc +++ b/ptam/src/ATANCamera.cc @@ -17,6 +17,12 @@ ATANCamera::ATANCamera(string sName) //mgvvCameraParams = mvDefaultParams; FixParams* pPars = ParamsAccess::fixParams; mgvvCameraParams = makeVector(pPars->Cam_fx, pPars->Cam_fy, pPars->Cam_cx, pPars->Cam_cy, pPars->Cam_s); + + + printf("Camera Parameters: fx: %f, fy: %f, cx: %f, cy: %f, dist: %f\n", + pPars->Cam_fx, pPars->Cam_fy, pPars->Cam_cx, pPars->Cam_cy, pPars->Cam_s); + + //GV2.Register(mgvvCameraParams, sName+".Parameters", mvDefaultParams, HIDDEN | FATAL_IF_NOT_DEFINED); //mvImageSize[0] = 640.0; //mvImageSize[1] = 480.0; From 82ee0b3e1f9310591ff95ca32680b07f1210ba44 Mon Sep 17 00:00:00 2001 From: JakobEngel Date: Sat, 27 Apr 2013 21:06:43 +0200 Subject: [PATCH 6/8] added missing header --- ptam/src/CameraCalibrator.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/ptam/src/CameraCalibrator.cc b/ptam/src/CameraCalibrator.cc index 47b46c5..0f57d59 100644 --- a/ptam/src/CameraCalibrator.cc +++ b/ptam/src/CameraCalibrator.cc @@ -16,6 +16,7 @@ #include #include +#include using namespace CVD; using namespace std; From c8b0173f3590a4e459c47785c9ad08895c665c4f Mon Sep 17 00:00:00 2001 From: Jakob Engel Date: Fri, 21 Feb 2014 17:57:29 +0100 Subject: [PATCH 7/8] * deleted rqt gui (not needed & requires more dependancies) * fixed segfault in ptam/src/CalibCornerPatch.cc * made working on any color images --- ptam/src/CalibCornerPatch.cc | 7 + ptam/src/CameraCalibrator.cc | 2 +- ptam/src/System.cc | 4 +- rqt_ptam/CMakeLists.txt | 50 --- rqt_ptam/Makefile | 1 - .../include/rqt_ptam/ratio_layouted_frame.h | 83 ----- rqt_ptam/include/rqt_ptam/remote_ptam.h | 121 ------- rqt_ptam/mainpage.dox | 6 - rqt_ptam/manifest.xml | 24 -- rqt_ptam/plugin.xml | 12 - .../src/rqt_ptam/ratio_layouted_frame.cpp | 116 ------- rqt_ptam/src/rqt_ptam/remote_ptam.cpp | 326 ------------------ rqt_ptam/src/rqt_ptam/remote_ptam.ui | 160 --------- 13 files changed, 10 insertions(+), 902 deletions(-) delete mode 100644 rqt_ptam/CMakeLists.txt delete mode 100644 rqt_ptam/Makefile delete mode 100644 rqt_ptam/include/rqt_ptam/ratio_layouted_frame.h delete mode 100644 rqt_ptam/include/rqt_ptam/remote_ptam.h delete mode 100644 rqt_ptam/mainpage.dox delete mode 100644 rqt_ptam/manifest.xml delete mode 100644 rqt_ptam/plugin.xml delete mode 100644 rqt_ptam/src/rqt_ptam/ratio_layouted_frame.cpp delete mode 100644 rqt_ptam/src/rqt_ptam/remote_ptam.cpp delete mode 100644 rqt_ptam/src/rqt_ptam/remote_ptam.ui diff --git a/ptam/src/CalibCornerPatch.cc b/ptam/src/CalibCornerPatch.cc index 4ac9ac9..9d6e69f 100644 --- a/ptam/src/CalibCornerPatch.cc +++ b/ptam/src/CalibCornerPatch.cc @@ -150,6 +150,13 @@ double CalibCornerPatch::Iterate(Image &im) { Vector<2> v2Pos_Template = vec(ir) - vec(mimTemplate.size() - ImageRef(1,1)) / 2.0; Vector<2> v2Pos_Image = mParams.v2Pos + v2Pos_Template; + if(!(v2Pos_Image[0] >= 0) || !(v2Pos_Image[1] >= 0)) + { + std::cout << "cought NAN, prevented segfault!\n"; + v2Pos_Image[0] = v2Pos_Image[1] = 100; + return 1e10; + } + double dDiff = imInterp[v2Pos_Image] - (mParams.dGain * mimTemplate[ir] + mParams.dMean); dSum += fabs(dDiff); Vector<6> v6Jac; diff --git a/ptam/src/CameraCalibrator.cc b/ptam/src/CameraCalibrator.cc index 0f57d59..c91874d 100644 --- a/ptam/src/CameraCalibrator.cc +++ b/ptam/src/CameraCalibrator.cc @@ -59,7 +59,7 @@ int main(int argc, char** argv) void CameraCalibrator::imageCallback(const sensor_msgs::ImageConstPtr & img) { - ROS_ASSERT(img->step == img->width); +// ROS_ASSERT(img->step == img->width); cv::Mat imgBW; if(img->encoding == sensor_msgs::image_encodings::RGB8) diff --git a/ptam/src/System.cc b/ptam/src/System.cc index 3e653fc..6b469e7 100644 --- a/ptam/src/System.cc +++ b/ptam/src/System.cc @@ -94,8 +94,8 @@ void System::imageCallback(const sensor_msgs::ImageConstPtr & img) // image-stub which will contain bw image cv::Mat imgBW; - ROS_ASSERT(img->step == img->width); - +// ROS_ASSERT(img->step == img->width); + if(img->encoding == sensor_msgs::image_encodings::RGB8) { // wrap around color data, and convert to bw image. diff --git a/rqt_ptam/CMakeLists.txt b/rqt_ptam/CMakeLists.txt deleted file mode 100644 index 105a063..0000000 --- a/rqt_ptam/CMakeLists.txt +++ /dev/null @@ -1,50 +0,0 @@ -cmake_minimum_required(VERSION 2.4.6) -include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) - -# Set the build type. Options are: -# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage -# Debug : w/ debug symbols, w/o optimization -# Release : w/o debug symbols, w/ optimization -# RelWithDebInfo : w/ debug symbols, w/ optimization -# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries -set(ROS_BUILD_TYPE Release) - -rosbuild_init() - -#set the default path for built executables to the "bin" directory -set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) -#set the default path for built libraries to the "lib" directory -set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) - - -find_package(Qt4 COMPONENTS QtCore QtGui REQUIRED) - -include(${QT_USE_FILE}) - -set(rqt_ptam_SRCS - src/rqt_ptam/remote_ptam.cpp - src/rqt_ptam/ratio_layouted_frame.cpp -) - -set(rqt_ptam_HDRS - include/rqt_ptam/remote_ptam.h - include/rqt_ptam/ratio_layouted_frame.h -) - -set(rqt_ptam_UIS - src/rqt_ptam/remote_ptam.ui -) - -set(rqt_ptam_INCLUDE_DIRECTORIES -# include - ${CMAKE_CURRENT_BINARY_DIR} -) - -qt4_wrap_cpp(rqt_ptam_MOCS ${rqt_ptam_HDRS} OPTIONS -DBOOST_TT_HAS_OPERATOR_HPP_INCLUDED -DBOOST_NO_TEMPLATE_PARTIAL_SPECIALIZATION) -qt4_wrap_ui(rqt_ptam_UIS_H ${rqt_ptam_UIS}) - -include_directories(${rqt_ptam_INCLUDE_DIRECTORIES} ) -rosbuild_add_library(rqt_ptam ${rqt_ptam_SRCS} ${rqt_ptam_MOCS} ${rqt_ptam_UIS_H}) -target_link_libraries(rqt_ptam ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY}) - - diff --git a/rqt_ptam/Makefile b/rqt_ptam/Makefile deleted file mode 100644 index b75b928..0000000 --- a/rqt_ptam/Makefile +++ /dev/null @@ -1 +0,0 @@ -include $(shell rospack find mk)/cmake.mk \ No newline at end of file diff --git a/rqt_ptam/include/rqt_ptam/ratio_layouted_frame.h b/rqt_ptam/include/rqt_ptam/ratio_layouted_frame.h deleted file mode 100644 index 10d7b9a..0000000 --- a/rqt_ptam/include/rqt_ptam/ratio_layouted_frame.h +++ /dev/null @@ -1,83 +0,0 @@ -/* - * Copyright (c) 2011, Dirk Thomas, TU Darmstadt - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the TU Darmstadt nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef rqt_image_view__RatioLayoutedFrame_H -#define rqt_image_view__RatioLayoutedFrame_H - -#include -#include -#include -#include -#include -#include - -namespace rqt_ptam { - -/** - * RatioLayoutedFrame is a layout containing a single frame with a fixed aspect ratio. - * The default aspect ratio is 4:3. - */ -class RatioLayoutedFrame - : public QFrame -{ - - Q_OBJECT - -public: - - RatioLayoutedFrame(QWidget* parent, Qt::WFlags flags = 0); - - virtual ~RatioLayoutedFrame(); - - QRect getAspectRatioCorrectPaintArea(); - - void resizeToFitAspectRatio(); - - void setInnerFrameMinimumSize(const QSize& size); - - void setInnerFrameMaximumSize(const QSize& size); - - void setInnerFrameFixedSize(const QSize& size); - - void setAspectRatio(unsigned short width, unsigned short height); - -private: - - static int greatestCommonDivisor(int a, int b); - - QSize aspect_ratio_; - -}; - -} - -#endif // rqt_image_view__RatioLayoutedFrame_H diff --git a/rqt_ptam/include/rqt_ptam/remote_ptam.h b/rqt_ptam/include/rqt_ptam/remote_ptam.h deleted file mode 100644 index 14a30c0..0000000 --- a/rqt_ptam/include/rqt_ptam/remote_ptam.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - - Copyright (c) 2013, Markus Achtelik, ASL, ETH Zurich, Switzerland - You can contact the author at - - * Copyright (c) 2011, Dirk Thomas, TU Darmstadt - - All rights reserved. - - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Neither the name of ETHZ-ASL nor the - names of its contributors may be used to endorse or promote products - derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY - DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - */ - - -#ifndef rqt_image_view__ImageView_H -#define rqt_image_view__ImageView_H - -#include - -#include - -#include -#include - -#include - -#include -#include -#include -#include -#include -#include - -#include - -namespace rqt_ptam { - -class RemotePTAM - : public rqt_gui_cpp::Plugin -{ - - Q_OBJECT - -public: - - RemotePTAM(); - - virtual void initPlugin(qt_gui_cpp::PluginContext& context); - - virtual bool eventFilter(QObject* watched, QEvent* event); - - virtual void shutdownPlugin(); - - virtual void saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const; - - virtual void restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings); - -protected slots: - - virtual void updateNamespaceList(); - -protected: - - virtual QList getTopicList(const QSet& message_types, const QList& transports); - - virtual void selectTopic(const QString& topic); - -protected slots: - - virtual void onNamespaceChanged(int index); - - virtual void onZoom1(bool checked); - - virtual void onSubscribe(bool checked); - - virtual void onSpace(); - - virtual void onReset(); - -protected: - - virtual void callbackImage(const sensor_msgs::Image::ConstPtr& msg); - - Ui::RemotePTAMWidget ui_; - - QWidget* widget_; - - image_transport::Subscriber subscriber_; - - ros::Publisher cmd_pub_; - - QImage qimage_; - QMutex qimage_mutex_; - - cv::Mat conversion_mat_; - -}; - -} - -#endif // rqt_image_view__ImageView_H diff --git a/rqt_ptam/mainpage.dox b/rqt_ptam/mainpage.dox deleted file mode 100644 index 93550db..0000000 --- a/rqt_ptam/mainpage.dox +++ /dev/null @@ -1,6 +0,0 @@ -/** -\mainpage -\htmlinclude manifest.html - -\b rqt_image_view provides a GUI plugin for displaying images using image_transport. -*/ diff --git a/rqt_ptam/manifest.xml b/rqt_ptam/manifest.xml deleted file mode 100644 index 690ff26..0000000 --- a/rqt_ptam/manifest.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - Remote PTAM plugin for rqt, based on rqt_image_view from Dirk Thomas, TU Darmstadt - - - Markus Achtelik - BSD - - http://ros.org/wiki/ethzasl_ptam/rqt_ptam - - - - - - - - - - - - - - diff --git a/rqt_ptam/plugin.xml b/rqt_ptam/plugin.xml deleted file mode 100644 index 4129cd8..0000000 --- a/rqt_ptam/plugin.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - A GUI plugin to remote control PTAM. - - - - image-x-generic - A GUI plugin to remote control ptam. - - - diff --git a/rqt_ptam/src/rqt_ptam/ratio_layouted_frame.cpp b/rqt_ptam/src/rqt_ptam/ratio_layouted_frame.cpp deleted file mode 100644 index da8fe57..0000000 --- a/rqt_ptam/src/rqt_ptam/ratio_layouted_frame.cpp +++ /dev/null @@ -1,116 +0,0 @@ -/* - * Copyright (c) 2011, Dirk Thomas, TU Darmstadt - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the TU Darmstadt nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#include - -#include - -namespace rqt_ptam { - -RatioLayoutedFrame::RatioLayoutedFrame(QWidget* parent, Qt::WFlags flags) - : QFrame() - , aspect_ratio_(4, 3) -{ -} - -RatioLayoutedFrame::~RatioLayoutedFrame() -{ -} - -void RatioLayoutedFrame::resizeToFitAspectRatio() -{ - QRect rect = contentsRect(); - - // reduce longer edge to aspect ration - double width = double(rect.width()); - double height = double(rect.height()); - if (width * aspect_ratio_.height() / height > aspect_ratio_.width()) - { - // too large width - width = height * aspect_ratio_.width() / aspect_ratio_.height(); - rect.setWidth(int(width)); - } - else - { - // too large height - height = width * aspect_ratio_.height() / aspect_ratio_.width(); - rect.setHeight(int(height)); - } - - // resize taking the border line into account - int border = lineWidth(); - resize(rect.width() + 2 * border, rect.height() + 2 * border); -} - -void RatioLayoutedFrame::setInnerFrameMinimumSize(const QSize& size) -{ - int border = lineWidth(); - QSize new_size = size; - new_size += QSize(2 * border, 2 * border); - setMinimumSize(new_size); - update(); -} - -void RatioLayoutedFrame::setInnerFrameMaximumSize(const QSize& size) -{ - int border = lineWidth(); - QSize new_size = size; - new_size += QSize(2 * border, 2 * border); - setMaximumSize(new_size); - update(); -} - -void RatioLayoutedFrame::setInnerFrameFixedSize(const QSize& size) -{ - setInnerFrameMinimumSize(size); - setInnerFrameMaximumSize(size); -} - -void RatioLayoutedFrame::setAspectRatio(unsigned short width, unsigned short height) -{ - int divisor = greatestCommonDivisor(width, height); - if (divisor != 0) { - aspect_ratio_.setWidth(width / divisor); - aspect_ratio_.setHeight(height / divisor); - } -} - -int RatioLayoutedFrame::greatestCommonDivisor(int a, int b) -{ - if (b==0) - { - return a; - } - return greatestCommonDivisor(b, a % b); -} - -} diff --git a/rqt_ptam/src/rqt_ptam/remote_ptam.cpp b/rqt_ptam/src/rqt_ptam/remote_ptam.cpp deleted file mode 100644 index 754bb93..0000000 --- a/rqt_ptam/src/rqt_ptam/remote_ptam.cpp +++ /dev/null @@ -1,326 +0,0 @@ -/* - - Copyright (c) 2013, Markus Achtelik, ASL, ETH Zurich, Switzerland - You can contact the author at - - * Copyright (c) 2011, Dirk Thomas, TU Darmstadt - - All rights reserved. - - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Neither the name of ETHZ-ASL nor the - names of its contributors may be used to endorse or promote products - derived from this software without specific prior written permission. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND - ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED - WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY - DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - */ - -#include - -#include -#include -#include -#include - -#include -#include - -#include -#include -#include - -namespace rqt_ptam { - -RemotePTAM::RemotePTAM() - : rqt_gui_cpp::Plugin() - , widget_(0) -{ - setObjectName("RemotePTAM"); -} - -void RemotePTAM::initPlugin(qt_gui_cpp::PluginContext& context) -{ - widget_ = new QWidget(); - ui_.setupUi(widget_); - - if (context.serialNumber() > 1) - { - widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")"); - } - context.addWidget(widget_); - - ui_.image_frame->installEventFilter(this); -// ui_.horizontalLayout->installEventFilter(this); -// ui_.horizontalLayout_2->installEventFilter(this); - - updateNamespaceList(); - ui_.topics_combo_box->setCurrentIndex(ui_.topics_combo_box->findText("")); - connect(ui_.topics_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(onNamespaceChanged(int))); - - ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh")); - connect(ui_.refresh_topics_push_button, SIGNAL(pressed()), this, SLOT(updateNamespaceList())); - - ui_.zoom_1_push_button->setIcon(QIcon::fromTheme("zoom-original")); - connect(ui_.zoom_1_push_button, SIGNAL(toggled(bool)), this, SLOT(onZoom1(bool))); - - connect(ui_.subscribe_check_box, SIGNAL(toggled(bool)), this, SLOT(onSubscribe(bool))); - - connect(ui_.space_push_button, SIGNAL(pressed()), this, SLOT(onSpace())); - - connect(ui_.reset_push_button, SIGNAL(pressed()), this, SLOT(onReset())); - - std::cout<<"test\n"; -} - -bool RemotePTAM::eventFilter(QObject* watched, QEvent* event) -{ - if (watched == ui_.image_frame && event->type() == QEvent::Paint) - { - QPainter painter(ui_.image_frame); - if (!qimage_.isNull()) - { - ui_.image_frame->resizeToFitAspectRatio(); - // TODO: check if full draw is really necessary - //QPaintEvent* paint_event = dynamic_cast(event); - //painter.drawImage(paint_event->rect(), qimage_); - qimage_mutex_.lock(); - painter.drawImage(ui_.image_frame->contentsRect(), qimage_); - qimage_mutex_.unlock(); - } else { - // default image with gradient - QLinearGradient gradient(0, 0, ui_.image_frame->frameRect().width(), ui_.image_frame->frameRect().height()); - gradient.setColorAt(0, Qt::white); - gradient.setColorAt(1, Qt::black); - painter.setBrush(gradient); - painter.drawRect(0, 0, ui_.image_frame->frameRect().width() + 1, ui_.image_frame->frameRect().height() + 1); - } - return false; - } - else if(event->type() == QEvent::KeyPress){ - QKeyEvent *key = static_cast(event); - if(key->key() == Qt::Key_Space) - onSpace(); - else if(key->key() == Qt::Key_R) - onReset(); - } - - return QObject::eventFilter(watched, event); -} - -void RemotePTAM::shutdownPlugin() -{ - subscriber_.shutdown(); - cmd_pub_.shutdown(); -} - -void RemotePTAM::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const -{ - QString topic = ui_.topics_combo_box->currentText(); - //qDebug("ImageView::saveSettings() topic '%s'", topic.toStdString().c_str()); - instance_settings.setValue("topic", topic); - instance_settings.setValue("zoom1", ui_.zoom_1_push_button->isChecked()); - } - -void RemotePTAM::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings) -{ - bool zoom1_checked = instance_settings.value("zoom1", false).toBool(); - ui_.zoom_1_push_button->setChecked(zoom1_checked); - - QString topic = instance_settings.value("topic", "").toString(); - //qDebug("ImageView::restoreSettings() topic '%s'", topic.toStdString().c_str()); - selectTopic(topic); -} - -void RemotePTAM::updateNamespaceList() -{ - QSet message_types; - QList transports; - message_types.insert("ptam_com/ptam_info"); - - QString selected = ui_.topics_combo_box->currentText(); - - // fill combo box - QList topics = getTopicList(message_types, transports); - topics.append(""); - qSort(topics); - ui_.topics_combo_box->clear(); - for (QList::const_iterator it = topics.begin(); it != topics.end(); it++) - { - - QString label(*it); - label.replace(" ", "/"); - label.replace("/info", ""); - -// std::cout<<"found "<toStdString()<<" "<addItem(label, QVariant(label)); - } - - // restore previous selection - selectTopic(selected); -} - -QList RemotePTAM::getTopicList(const QSet& message_types, const QList& transports) -{ - ros::master::V_TopicInfo topic_info; - ros::master::getTopics(topic_info); - - QSet all_topics; - for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) - { - all_topics.insert(it->name.c_str()); - } - - QList topics; - for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++) - { - if (message_types.contains(it->datatype.c_str())) - { - QString topic = it->name.c_str(); - - // add raw topic - topics.append(topic); - //qDebug("ImageView::getTopicList() raw topic '%s'", topic.toStdString().c_str()); - - // add transport specific sub-topics - for (QList::const_iterator jt = transports.begin(); jt != transports.end(); jt++) - { - if (all_topics.contains(topic + "/" + *jt)) - { - QString sub = topic + " " + *jt; - topics.append(sub); - //qDebug("ImageView::getTopicList() transport specific sub-topic '%s'", sub.toStdString().c_str()); - } - } - } - } - return topics; -} - -void RemotePTAM::selectTopic(const QString& topic) -{ - int index = ui_.topics_combo_box->findText(topic); - if (index == -1) - { - index = ui_.topics_combo_box->findText(""); - } - ui_.topics_combo_box->setCurrentIndex(index); -} - -void RemotePTAM::onNamespaceChanged(int index) -{ - subscriber_.shutdown(); - - // reset image on topic change - qimage_ = QImage(); - ui_.image_frame->update(); - - QStringList parts = ui_.topics_combo_box->itemData(index).toString().split(" "); - QString topic = parts.first(); - - std::cout<<"topic"<(topic.toStdString() + "/key_pressed", 10); - image_transport::ImageTransport it(nh); - try { - subscriber_ = it.subscribe(topic.toStdString() + "/preview", 1, &RemotePTAM::callbackImage, this); - //qDebug("ImageView::onTopicChanged() to topic '%s' with transport '%s'", topic.toStdString().c_str(), subscriber_.getTransport().c_str()); - } catch (image_transport::TransportLoadException& e) { - QMessageBox::warning(widget_, tr("Loading image transport plugin failed"), e.what()); - } - } -} - -void RemotePTAM::onZoom1(bool checked) -{ - if (checked) - { - if (qimage_.isNull()) - { - return; - } - ui_.image_frame->setInnerFrameFixedSize(qimage_.size()); - widget_->resize(ui_.image_frame->size()); - widget_->setMinimumSize(widget_->sizeHint()); - widget_->setMaximumSize(widget_->sizeHint()); - } else { - ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60)); - ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX)); - widget_->setMinimumSize(QSize(80, 60)); - widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX)); - } -} - -void RemotePTAM::onSubscribe(bool checked) -{ -// TODO subscribe / unsubscribe -} - -void RemotePTAM::callbackImage(const sensor_msgs::Image::ConstPtr& msg) -{ - try - { - // First let cv_bridge do its magic - cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8); - conversion_mat_ = cv_ptr->image; - } - catch (cv_bridge::Exception& e) - { - ROS_WARN_STREAM("image conversion failed. Reason: "<< e.what()); - } - - // copy temporary image as it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation - QImage image(conversion_mat_.data, conversion_mat_.cols, conversion_mat_.rows, QImage::Format_RGB888); - qimage_mutex_.lock(); - qimage_ = image.copy(); - qimage_mutex_.unlock(); - - ui_.image_frame->setAspectRatio(qimage_.width(), qimage_.height()); - if (!ui_.zoom_1_push_button->isEnabled()) - { - ui_.zoom_1_push_button->setEnabled(true); - onZoom1(ui_.zoom_1_push_button->isChecked()); - } - ui_.image_frame->update(); -} - -void RemotePTAM::onReset() -{ - std::cout << "Sending \"r\" to ptam" << std::endl; - std_msgs::StringPtr msg(new std_msgs::String); - msg->data = "r"; - cmd_pub_.publish(msg); -} - -void RemotePTAM::onSpace() -{ - std::cout << "Sending \"Space\" to ptam" << std::endl; - std_msgs::StringPtr msg(new std_msgs::String); - msg->data = "Space"; - cmd_pub_.publish(msg); -} - - -} - -PLUGINLIB_EXPORT_CLASS(rqt_ptam::RemotePTAM, rqt_gui_cpp::Plugin) diff --git a/rqt_ptam/src/rqt_ptam/remote_ptam.ui b/rqt_ptam/src/rqt_ptam/remote_ptam.ui deleted file mode 100644 index 532cfda..0000000 --- a/rqt_ptam/src/rqt_ptam/remote_ptam.ui +++ /dev/null @@ -1,160 +0,0 @@ - - - RemotePTAMWidget - - - true - - - - 0 - 0 - 502 - 300 - - - - Remote PTAM - - - - - - - - QComboBox::AdjustToContents - - - - - - - - - - false - - - true - - - - - - - subscribe to ptam image - - - - - - - - - - send "space" to ptam - - - space - - - - - - - resets the map - - - reset - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - 0 - - - - - - 0 - 0 - - - - - 80 - 60 - - - - Qt::ClickFocus - - - QFrame::Box - - - 1 - - - - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 0 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 0 - - - - - - - - - rqt_ptam::RatioLayoutedFrame - QFrame -
rqt_ptam/ratio_layouted_frame.h
- 1 -
-
- - -
From 1a11a65cf883ff3dbcf24ee4a0896805d226a707 Mon Sep 17 00:00:00 2001 From: Jakob Engel Date: Tue, 2 Dec 2014 11:59:39 +0100 Subject: [PATCH 8/8] added option to load from images --- ptam/CMakeLists.txt | 3 + ptam/src/CameraCalibrator.cc | 106 +++++++++++++++++++++++++++++++++++ ptam/src/Params.cpp | 14 ++--- 3 files changed, 116 insertions(+), 7 deletions(-) diff --git a/ptam/CMakeLists.txt b/ptam/CMakeLists.txt index f8df952..c03ece3 100644 --- a/ptam/CMakeLists.txt +++ b/ptam/CMakeLists.txt @@ -110,6 +110,9 @@ target_link_libraries(ptam ${PTAM_LIBRARIES} ${OpenCV_LIBS}) # Camera calibrator rosbuild_add_executable(cameracalibrator ${CALIBRATOR_FILES}) target_link_libraries(cameracalibrator ${PTAM_LIBRARIES} ${OpenCV_LIBS}) +rosbuild_link_boost(cameracalibrator filesystem) +rosbuild_link_boost(cameracalibrator system) + # PTAM remote control # this is unfortunately neccessary to close app, when opencvwindow gets closed diff --git a/ptam/src/CameraCalibrator.cc b/ptam/src/CameraCalibrator.cc index c91874d..5948340 100644 --- a/ptam/src/CameraCalibrator.cc +++ b/ptam/src/CameraCalibrator.cc @@ -106,6 +106,9 @@ void CameraCalibrator::init() { mGLWindow = new GLWindow2(mCurrentImage.size(), "Camera Calibrator"); + mbDone = false; + + GUI.RegisterCommand("CameraCalibrator.GrabImages", GUICommandCallBack, this); GUI.RegisterCommand("CameraCalibrator.GrabNextFrame", GUICommandCallBack, this); GUI.RegisterCommand("CameraCalibrator.Reset", GUICommandCallBack, this); GUI.RegisterCommand("CameraCalibrator.ShowNext", GUICommandCallBack, this); @@ -118,6 +121,7 @@ void CameraCalibrator::init() GV3::Register(mgvnDisableDistortion, "CameraCalibrator.NoDistortion", 0, SILENT); GUI.ParseLine("GLWindow.AddMenu CalibMenu"); + GUI.ParseLine("CalibMenu.AddMenuButton Live GrabImages CameraCalibrator.GrabImages"); GUI.ParseLine("CalibMenu.AddMenuButton Live GrabFrame CameraCalibrator.GrabNextFrame"); GUI.ParseLine("CalibMenu.AddMenuButton Live Reset CameraCalibrator.Reset"); GUI.ParseLine("CalibMenu.AddMenuButton Live Optimize \"CameraCalibrator.Optimize=1\""); @@ -241,6 +245,25 @@ void CameraCalibrator::GUICommandCallBack(void* ptr, string sCommand, string sPa ((CameraCalibrator*)ptr)->GUICommandHandler(sCommand, sParams); } + +#include +#include +#include +#include "boost/filesystem/operations.hpp" +#include "boost/filesystem/path.hpp" +namespace fs = boost::filesystem; + +void conversionCVToNB(cv::Mat frame, Image &imBW, ATANCamera& mCamera){ + cv::Mat clone = frame.clone(); + cv::Mat_& frame_p = (cv::Mat_&)clone; + for (int i = 0; i < mCamera.GetImageSize()[1]; i++){ + for (int j = 0; j < mCamera.GetImageSize()[0]; j++){ + imBW[i][j] = (frame_p(i,j)[0] + frame_p(i,j)[1] + frame_p(i,j)[2]) / 3; + } + } + +} + void CameraCalibrator::GUICommandHandler(string sCommand, string sParams) // Called by the callback func.. { if (sCommand == "CameraCalibrator.Reset") @@ -278,6 +301,89 @@ void CameraCalibrator::GUICommandHandler(string sCommand, string sParams) // Cal } mbDone = true; } +if(sCommand=="CameraCalibrator.GrabImages") + { + fs::path full_path( fs::initial_path() ); + full_path = fs::system_complete( fs::path( "Images/" ) ); + + if ( !fs::exists( full_path ) ) + { + std::cout << "\nNot found: " << full_path.c_str() << std::endl; + return; + } + + if ( fs::is_directory( full_path ) ) + { + std::cout << "\nIn directory: " + << full_path.c_str() << "\n\n"; + fs::directory_iterator end_iter; + for ( fs::directory_iterator dir_itr( full_path ); + dir_itr != end_iter; + ++dir_itr ) + { + try + { + if ( fs::is_directory( dir_itr->status() ) ) + { +// ++dir_count; +// std::cout << dir_itr->path().filename() << " [directory]\n"; + } + else if ( fs::is_regular_file( dir_itr->status() ) ) + { +// ++file_count; +// std::cout << dir_itr->path().filename() << "\n"; + + cv::Mat image; + image = cv::imread(dir_itr->path().c_str()); + printf("path: %s\n", dir_itr->path().c_str()); +// cv::Mat grayImage; +// cvtColor(image, grayImage, CV_RGB2GRAY); +// printf("1\n"); + + Image imBW(mCurrentImage.size()); + conversionCVToNB(image, imBW, mCamera); + + // TODO: display 3D points + glDrawPixels(imBW); + + CalibImage c; + if(c.MakeFromImage(imBW)) + { + printf("Using image %s\n", dir_itr->path().filename().c_str()); + mvCalibImgs.push_back(c); + mvCalibImgs.back().GuessInitialPose(mCamera); + + // TODO: display 3D points + //mvCalibImgs.back().Draw3DGrid(mCamera, false); + mGLWindow->HandlePendingEvents(); + mGLWindow->swap_buffers(); + //sleep(3); + } + else + { + printf("NOT using image %s\n", dir_itr->path().filename().c_str()); + } + } + else + { +// ++other_count; +// std::cout << dir_itr->path().filename() << " [other]\n"; + } + + } + catch ( const std::exception & ex ) + { +// ++err_count; + std::cout << dir_itr->path().filename().c_str() << " " << ex.what() << std::endl; + } + } +// std::cout << "\n" << file_count << " files\n" +// << dir_count << " directories\n" +// << other_count << " others\n" +// << err_count << " errors\n"; + } + + } if (sCommand == "exit" || sCommand == "quit") { mbDone = true; diff --git a/ptam/src/Params.cpp b/ptam/src/Params.cpp index e61f083..639a638 100644 --- a/ptam/src/Params.cpp +++ b/ptam/src/Params.cpp @@ -30,7 +30,7 @@ void FixParams::readFixParams() // ROS_BREAK(); } - nh.param("ImageSizeX", ImageSizeX, 640); + nh.param("ImageSizeX", ImageSizeX, 752); nh.param("ImageSizeY", ImageSizeY, 480); nh.param("ARBuffer_width", ARBuffer_width, 1200); nh.param("ARBuffer_height", ARBuffer_height, 900); @@ -39,11 +39,11 @@ void FixParams::readFixParams() nh.param("TrackerMEstimator", TrackerMEstimator, std::string("Tukey")); nh.param("MinTukeySigma", MinTukeySigma, 0.4); nh.param("CandidateMinSTScore", CandidateMinSTScore, 70); - // nh.param("Cam_fx", Cam_fx,0.392); - // nh.param("Cam_fy", Cam_fy,0.613); - // nh.param("Cam_cx", Cam_cx,0.484); - // nh.param("Cam_cy", Cam_cy,0.476); - // nh.param("Cam_s", Cam_s,0.967); + nh.param("Cam_fx", Cam_fx,0.392); + nh.param("Cam_fy", Cam_fy,0.613); + nh.param("Cam_cx", Cam_cx,0.484); + nh.param("Cam_cy", Cam_cy,0.476); + nh.param("Cam_s", Cam_s,0.967); nh.param("Calibrator_BlurSigma", Calibrator_BlurSigma, 1.0); nh.param("Calibrator_MeanGate", Calibrator_MeanGate, 10.0); nh.param("Calibrator_MinCornersForGrabbedImage", Calibrator_MinCornersForGrabbedImage, 20); @@ -57,6 +57,6 @@ void FixParams::readFixParams() nh.param("GLWindowMenu_mgvnMenuTextOffset", GLWindowMenu_mgvnMenuTextOffset, 20); nh.param("InitLevel", InitLevel, 1); nh.param("parent_frame", parent_frame, std::string("world")); - nh.param("gui", gui, false); + nh.param("gui", gui, true); } ;