From f4dabfb1958dd93801a30c9fa7d638a6a8c94c7b Mon Sep 17 00:00:00 2001 From: Nicolas Pope <nwpope@utu.fi> Date: Thu, 18 Jul 2019 09:10:42 +0300 Subject: [PATCH] Code tidy --- applications/calibration/src/align.cpp | 15 ++--- applications/calibration/src/common.cpp | 10 +-- applications/gui/src/camera.cpp | 4 -- applications/gui/src/camera.hpp | 1 - applications/gui/src/config_window.cpp | 2 +- applications/gui/src/pose_window.cpp | 2 +- applications/gui/src/screen.cpp | 2 +- applications/gui/src/src_window.cpp | 63 +------------------ applications/reconstruct/src/main.cpp | 5 +- applications/reconstruct/src/splat_render.cpp | 8 +-- applications/reconstruct/src/splat_render.cu | 8 +-- applications/reconstruct/src/voxel_scene.cpp | 2 +- components/common/cpp/src/configuration.cpp | 1 - components/control/cpp/src/slave.cpp | 8 +-- components/net/cpp/include/ftl/net/peer.hpp | 2 +- components/net/cpp/src/dispatcher.cpp | 6 +- .../rgbd-sources/src/cb_segmentation.cpp | 14 ++--- components/rgbd-sources/src/colour.cpp | 6 +- 18 files changed, 42 insertions(+), 117 deletions(-) diff --git a/applications/calibration/src/align.cpp b/applications/calibration/src/align.cpp index bbf6f0f2e..01123aea9 100644 --- a/applications/calibration/src/align.cpp +++ b/applications/calibration/src/align.cpp @@ -62,7 +62,7 @@ inline std::string getOption(map<string, string> &options, const std::string &op static const float kPI = 3.14159f; -static float calculateZRotation(const vector<Point2f> &points, Size &boardSize) { +/*static float calculateZRotation(const vector<Point2f> &points, Size &boardSize) { Point2f tl = points[boardSize.width * (boardSize.height / 2)]; Point2f tr = points[boardSize.width * (boardSize.height / 2) + boardSize.width-1]; @@ -87,7 +87,7 @@ static Point2f parallaxDistortion(const vector<Point2f> &points, Size &boardSize float ddy = dy1 - dy2; return Point2f(ddx, ddy); -} +}*/ static float distanceTop(const Mat &camMatrix, const vector<Point2f> &points, Size &boardSize, float squareSize) { Point2f tl = points[0]; @@ -142,7 +142,7 @@ static Rec4f distances(const Mat &camMatrix, const vector<Point2f> &points, Size }; } -static float distance(const Mat &camMatrix, const vector<Point2f> &points, Size &boardSize, float squareSize) { +/*static float distance(const Mat &camMatrix, const vector<Point2f> &points, Size &boardSize, float squareSize) { Point2f tl = points[boardSize.width * (boardSize.height / 2)]; Point2f tr = points[boardSize.width * (boardSize.height / 2) + boardSize.width-1]; @@ -164,7 +164,7 @@ static Point2f diffY(const vector<Point2f> &pointsA, const vector<Point2f> &poin float d2 = trA.y - trB.y; return Point2f(d1,d2); -} +}*/ static const float kDistanceThreshold = 0.005f; @@ -237,7 +237,6 @@ void ftl::calibration::align(map<string, string> &opt) { } #endif - int step = 0; bool anaglyph = true; while (true) { @@ -292,14 +291,11 @@ void ftl::calibration::align(map<string, string> &opt) { // TODO Check angles also... bool lrValid = std::abs(dists.left-dists.right) <= kDistanceThreshold; bool tbValid = std::abs(dists.top-dists.bottom) <= kDistanceThreshold; - bool distValid = lrValid & tbValid; bool tiltUp = dists.top < dists.bottom && !tbValid; bool tiltDown = dists.top > dists.bottom && !tbValid; bool rotLeft = dists.left > dists.right && !lrValid; bool rotRight = dists.left < dists.right && !lrValid; - float d = (dists.left + dists.right + dists.top + dists.bottom) / 4.0f; - // TODO Draw lines Point2f bl = pointBufA[(boardSize.height-1)*boardSize.width]; Point2f tl = pointBufA[0]; @@ -350,14 +346,11 @@ void ftl::calibration::align(map<string, string> &opt) { // TODO Check angles also... bool lrValid = std::abs(dists.left-dists.right) <= kDistanceThreshold; bool tbValid = std::abs(dists.top-dists.bottom) <= kDistanceThreshold; - bool distValid = lrValid & tbValid; bool tiltUp = dists.top < dists.bottom && !tbValid; bool tiltDown = dists.top > dists.bottom && !tbValid; bool rotLeft = dists.left > dists.right && !lrValid; bool rotRight = dists.left < dists.right && !lrValid; - float d = (dists.left + dists.right + dists.top + dists.bottom) / 4.0f; - // TODO Draw lines Point2f bbl = pointBufB[(boardSize.height-1)*boardSize.width]; Point2f btl = pointBufB[0]; diff --git a/applications/calibration/src/common.cpp b/applications/calibration/src/common.cpp index c68f105e1..69b759eb2 100644 --- a/applications/calibration/src/common.cpp +++ b/applications/calibration/src/common.cpp @@ -120,7 +120,7 @@ Grid::Grid(int rows, int cols, int width, int height, } void Grid::drawGrid(Mat &rgb) { - for (size_t i = 0; i < rows_ * cols_; ++i) { + for (int i = 0; i < rows_ * cols_; ++i) { bool visited = visited_[i]; cv::Scalar color = visited ? cv::Scalar(24, 255, 24) : cv::Scalar(24, 24, 255); cv::rectangle(rgb, corners_[i].first, corners_[i].second, color, 2); @@ -130,7 +130,7 @@ void Grid::drawGrid(Mat &rgb) { int Grid::checkGrid(cv::Point p1, cv::Point p2) { // TODO calculate directly - for (size_t i = 0; i < rows_ * cols_; ++i) { + for (int i = 0; i < rows_ * cols_; ++i) { auto &corners = corners_[i]; if (p1.x >= corners.first.x && p1.x <= corners.second.x && @@ -148,21 +148,21 @@ int Grid::checkGrid(cv::Point p1, cv::Point p2) { } void Grid::updateGrid(int i) { - if (i >= 0 && i < visited_.size() && !visited_[i]) { + if (i >= 0 && i < static_cast<int>(visited_.size()) && !visited_[i]) { visited_[i] = true; visited_count_ += 1; } } bool Grid::isVisited(int i) { - if (i >= 0 && i < visited_.size()) { + if (i >= 0 && i < static_cast<int>(visited_.size())) { return visited_[i]; } return false; } bool Grid::isComplete() { - return visited_count_ == visited_.size(); + return visited_count_ == static_cast<int>(visited_.size()); } void Grid::reset() { diff --git a/applications/gui/src/camera.cpp b/applications/gui/src/camera.cpp index 54b7fb09a..8869cff1e 100644 --- a/applications/gui/src/camera.cpp +++ b/applications/gui/src/camera.cpp @@ -239,10 +239,6 @@ void ftl::gui::Camera::setChannel(ftl::rgbd::channel_t c) { } } -const GLTexture &ftl::gui::Camera::thumbnail() { - return GLTexture(); -} - const GLTexture &ftl::gui::Camera::captureFrame() { float now = (float)glfwGetTime(); delta_ = now - ftime_; diff --git a/applications/gui/src/camera.hpp b/applications/gui/src/camera.hpp index 034fcf853..8d48e2c06 100644 --- a/applications/gui/src/camera.hpp +++ b/applications/gui/src/camera.hpp @@ -38,7 +38,6 @@ class Camera { void isPaused(); const std::vector<ftl::rgbd::channel_t> &availableChannels(); - const GLTexture &thumbnail(); const GLTexture &captureFrame(); nlohmann::json getMetaData(); diff --git a/applications/gui/src/config_window.cpp b/applications/gui/src/config_window.cpp index cc422f495..a9db26b46 100644 --- a/applications/gui/src/config_window.cpp +++ b/applications/gui/src/config_window.cpp @@ -26,7 +26,7 @@ ConfigWindow::ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl, con configurables_ = ctrl->getConfigurables(peer); - auto label = new Label(this, "Select Configurable","sans-bold"); + new Label(this, "Select Configurable","sans-bold"); auto select = new ComboBox(this, configurables_); select->setCallback([this](int ix) { diff --git a/applications/gui/src/pose_window.cpp b/applications/gui/src/pose_window.cpp index d1afdb739..2277c27c5 100644 --- a/applications/gui/src/pose_window.cpp +++ b/applications/gui/src/pose_window.cpp @@ -22,7 +22,7 @@ static Eigen::Affine3d create_rotation_matrix(float ax, float ay, float az) { } PoseWindow::PoseWindow(ftl::gui::Screen *screen, const std::string &src) - : nanogui::Window(screen, "Pose Adjust"), screen_(screen), src_(src) { + : nanogui::Window(screen, "Pose Adjust"), src_(src), screen_(screen) { using namespace nanogui; //setLayout(new nanogui::GroupLayout()); diff --git a/applications/gui/src/screen.cpp b/applications/gui/src/screen.cpp index 32b54c630..56624ce61 100644 --- a/applications/gui/src/screen.cpp +++ b/applications/gui/src/screen.cpp @@ -298,7 +298,7 @@ bool ftl::gui::Screen::mouseButtonEvent(const nanogui::Vector2i &p, int button, } camPos *= -1.0f; - Eigen::Vector4f worldPos = camera_->source()->getPose().cast<float>() * camPos; + //Eigen::Vector4f worldPos = camera_->source()->getPose().cast<float>() * camPos; //lookPoint_ = Eigen::Vector3f(worldPos[0],worldPos[1],worldPos[2]); LOG(INFO) << "Depth at click = " << -camPos[2]; return true; diff --git a/applications/gui/src/src_window.cpp b/applications/gui/src/src_window.cpp index cebbb325f..e98ec081b 100644 --- a/applications/gui/src/src_window.cpp +++ b/applications/gui/src/src_window.cpp @@ -43,7 +43,7 @@ SourceWindow::SourceWindow(ftl::gui::Screen *screen) // tools->setLayout(new BoxLayout(Orientation::Horizontal, // Alignment::Middle, 0, 6)); - auto label = new Label(this, "Select Camera","sans-bold",20); + new Label(this, "Select Camera","sans-bold",20); //auto select = new ComboBox(this, available_); //select->setCallback([this,select](int ix) { @@ -73,65 +73,6 @@ SourceWindow::SourceWindow(ftl::gui::Screen *screen) } _updateCameras(screen_->control()->getNet()->findAll<string>("list_streams")); - - /*new Label(this, "Source Options","sans-bold"); - - auto tools = new Widget(this); - tools->setLayout(new BoxLayout(Orientation::Horizontal, - Alignment::Middle, 0, 6)); - - auto button_rgb = new Button(tools, "RGB"); - button_rgb->setTooltip("RGB left image"); - button_rgb->setFlags(Button::RadioButton); - button_rgb->setPushed(true); - button_rgb->setChangeCallback([this](bool state) { mode_ = Mode::rgb; }); - - auto button_depth = new Button(tools, "Depth"); - button_depth->setFlags(Button::RadioButton); - button_depth->setChangeCallback([this](bool state) { mode_ = Mode::depth; }); - - auto button_stddev = new Button(tools, "SD. 25"); - button_stddev->setTooltip("Standard Deviation over 25 frames"); - button_stddev->setFlags(Button::RadioButton); - button_stddev->setChangeCallback([this](bool state) { mode_ = Mode::stddev; }); - - //auto button_pose = new Button(this, "Adjust Pose", ENTYPO_ICON_COMPASS); - //button_pose->setCallback([this]() { - // auto posewin = new PoseWindow(screen_, screen_->control(), src_->getURI()); - // posewin->setTheme(theme()); - //}); - -#ifdef HAVE_LIBARCHIVE - auto button_snapshot = new Button(this, "Snapshot", ENTYPO_ICON_IMAGES); - button_snapshot->setCallback([this] { - try { - /*char timestamp[18]; - std::time_t t=std::time(NULL); - std::strftime(timestamp, sizeof(timestamp), "%F-%H%M%S", std::localtime(&t)); - auto writer = ftl::rgbd::SnapshotWriter(std::string(timestamp) + ".tar.gz"); - cv::Mat rgb, depth; - this->src_->getFrames(rgb, depth); - if (!writer.addCameraRGBD( - "0", // TODO - rgb, - depth, - this->src_->getPose(), - this->src_->parameters() - )) { - LOG(ERROR) << "Snapshot failed"; - } - } - catch(std::runtime_error) { - LOG(ERROR) << "Snapshot failed (file error)"; - } - }); -#endif - - //auto imageView = new VirtualCameraView(this); - //cam.view = imageView; - //imageView->setGridThreshold(20); - //imageView->setSource(src_); - //image_ = imageView;*/ } void SourceWindow::_updateCameras(const vector<string> &netcams) { @@ -182,7 +123,7 @@ void SourceWindow::draw(NVGcontext *ctx) { } } - if (ipanel_->childCount() < i+1) { + if ((size_t)ipanel_->childCount() < i+1) { new ftl::gui::ThumbView(ipanel_, screen_, cam); } if (thumbs_[i].isValid()) dynamic_cast<nanogui::ImageView*>(ipanel_->childAt(i))->bindImage(thumbs_[i].texture()); diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp index 4a3f9b823..650c74b61 100644 --- a/applications/reconstruct/src/main.cpp +++ b/applications/reconstruct/src/main.cpp @@ -99,16 +99,13 @@ static void run(ftl::Configurable *root) { //virtimpl->setScene(scene); stream->add(virt); - for (int i=0; i<sources.size(); i++) { + for (size_t i=0; i<sources.size(); i++) { Source *in = sources[i]; in->setChannel(ftl::rgbd::kChanDepth); stream->add(in); scene->addSource(in); } - unsigned char frameCount = 0; - bool paused = false; - int active = sources.size(); while (ftl::running) { if (active == 0) { diff --git a/applications/reconstruct/src/splat_render.cpp b/applications/reconstruct/src/splat_render.cpp index 267620895..cb513c1da 100644 --- a/applications/reconstruct/src/splat_render.cpp +++ b/applications/reconstruct/src/splat_render.cpp @@ -19,16 +19,16 @@ void Splatter::render(ftl::rgbd::Source *src, cudaStream_t stream) { cudaSafeCall(cudaSetDevice(scene_->getCUDADevice())); - if (depth1_.width() != camera.width || depth1_.height() != camera.height) { + if ((unsigned int)depth1_.width() != camera.width || (unsigned int)depth1_.height() != camera.height) { depth1_ = ftl::cuda::TextureObject<uint>(camera.width, camera.height); } - if (colour1_.width() != camera.width || colour1_.height() != camera.height) { + if ((unsigned int)colour1_.width() != camera.width || (unsigned int)colour1_.height() != camera.height) { colour1_ = ftl::cuda::TextureObject<uchar4>(camera.width, camera.height); } - if (depth2_.width() != camera.width || depth2_.height() != camera.height) { + if ((unsigned int)depth2_.width() != camera.width || (unsigned int)depth2_.height() != camera.height) { depth2_ = ftl::cuda::TextureObject<float>(camera.width, camera.height); } - if (colour2_.width() != camera.width || colour2_.height() != camera.height) { + if ((unsigned int)colour2_.width() != camera.width || (unsigned int)colour2_.height() != camera.height) { colour2_ = ftl::cuda::TextureObject<uchar4>(camera.width, camera.height); } diff --git a/applications/reconstruct/src/splat_render.cu b/applications/reconstruct/src/splat_render.cu index 4ef0b233c..12be18e04 100644 --- a/applications/reconstruct/src/splat_render.cu +++ b/applications/reconstruct/src/splat_render.cu @@ -238,8 +238,8 @@ __global__ void splatting_kernel( const int x = bx + threadIdx.x; const int y = by + threadIdx.y; - const float camMinDepth = params.camera.m_sensorDepthWorldMin; - const float camMaxDepth = params.camera.m_sensorDepthWorldMax; + // const float camMinDepth = params.camera.m_sensorDepthWorldMin; + // const float camMaxDepth = params.camera.m_sensorDepthWorldMax; for (int j=i; j<SPLAT_BUFFER_SIZE; j+=T_PER_BLOCK) { const unsigned int sx = (j % SPLAT_BOUNDS)+bx-SPLAT_RADIUS; @@ -258,7 +258,7 @@ __global__ void splatting_kernel( const float voxelSquared = params.voxelSize*params.voxelSize; float mindepth = 1000.0f; int minidx = -1; - float3 minpos; + // float3 minpos; //float3 validPos[MAX_VALID]; int validIndices[MAX_VALID]; @@ -283,7 +283,7 @@ __global__ void splatting_kernel( if (d < mindepth) { mindepth = d; minidx = idx; - minpos = pos; + // minpos = pos; } } } diff --git a/applications/reconstruct/src/voxel_scene.cpp b/applications/reconstruct/src/voxel_scene.cpp index e514e2640..e392f55ee 100644 --- a/applications/reconstruct/src/voxel_scene.cpp +++ b/applications/reconstruct/src/voxel_scene.cpp @@ -25,7 +25,7 @@ extern "C" void integrateDepthMapCUDA(ftl::voxhash::HashData& hashData, const ft //extern "C" void bindInputDepthColorTextures(const DepthCameraData& depthCameraData); -SceneRep::SceneRep(nlohmann::json &config) : Configurable(config), do_reset_(false), m_frameCount(0) { +SceneRep::SceneRep(nlohmann::json &config) : Configurable(config), m_frameCount(0), do_reset_(false) { _initCUDA(); // Allocates voxel structure on GPU diff --git a/components/common/cpp/src/configuration.cpp b/components/common/cpp/src/configuration.cpp index 79caa6d41..991fdc120 100644 --- a/components/common/cpp/src/configuration.cpp +++ b/components/common/cpp/src/configuration.cpp @@ -171,7 +171,6 @@ static void _indexConfig(json_t &cfg) { if (cfg.is_object()) { auto id = cfg["$id"]; if (id.is_string()) { - LOG(INFO) << "Indexing: " << id.get<string>(); config_index[id.get<string>()] = &cfg; } diff --git a/components/control/cpp/src/slave.cpp b/components/control/cpp/src/slave.cpp index 88933ed7a..cd2d0f1ff 100644 --- a/components/control/cpp/src/slave.cpp +++ b/components/control/cpp/src/slave.cpp @@ -7,10 +7,10 @@ using ftl::net::Universe; using ftl::ctrl::Slave; using std::string; -static void netLog(void* user_data, const loguru::Message& message) { - Slave *slave = static_cast<Slave*>(user_data); - slave->sendLog(message); -} +// static void netLog(void* user_data, const loguru::Message& message) { +// Slave *slave = static_cast<Slave*>(user_data); +// slave->sendLog(message); +// } Slave::Slave(Universe *net, ftl::Configurable *root) : net_(net), in_log_(false), active_(true) { diff --git a/components/net/cpp/include/ftl/net/peer.hpp b/components/net/cpp/include/ftl/net/peer.hpp index f58ab004e..14c021861 100644 --- a/components/net/cpp/include/ftl/net/peer.hpp +++ b/components/net/cpp/include/ftl/net/peer.hpp @@ -331,7 +331,7 @@ int Peer::asyncCall( callbacks_[rpcid] = std::make_unique<caller<T>>(cb); } - LOG(INFO) << "RPC " << name << "(" << rpcid << ") -> " << uri_; + DLOG(INFO) << "RPC " << name << "(" << rpcid << ") -> " << uri_; auto call_obj = std::make_tuple(0,rpcid,name,args_obj); diff --git a/components/net/cpp/src/dispatcher.cpp b/components/net/cpp/src/dispatcher.cpp index ec5781d6a..34b01238a 100644 --- a/components/net/cpp/src/dispatcher.cpp +++ b/components/net/cpp/src/dispatcher.cpp @@ -65,15 +65,15 @@ void ftl::net::Dispatcher::dispatch_call(Peer &s, const msgpack::object &msg) { // assert(type == 0); if (type == 1) { - LOG(INFO) << "RPC return for " << id; + DLOG(INFO) << "RPC return for " << id; s._dispatchResponse(id, args); } else if (type == 0) { - LOG(INFO) << "RPC " << name << "() <- " << s.getURI(); + DLOG(INFO) << "RPC " << name << "() <- " << s.getURI(); auto func = _locateHandler(name); if (func) { - LOG(INFO) << "Found binding for " << name; + DLOG(INFO) << "Found binding for " << name; try { auto result = (*func)(args); //->get(); s._sendResponse(id, result->get()); diff --git a/components/rgbd-sources/src/cb_segmentation.cpp b/components/rgbd-sources/src/cb_segmentation.cpp index f6f5fc2b2..102524c10 100644 --- a/components/rgbd-sources/src/cb_segmentation.cpp +++ b/components/rgbd-sources/src/cb_segmentation.cpp @@ -83,9 +83,9 @@ CBSegmentation::CBSegmentation( char codebook_size, size_t width, size_t height, float alpha, float beta, float epsilon, float sigma, int T_h, int T_add, int T_del) : - size_(codebook_size + 1), width_(width), height_(height), - alpha_(alpha), beta_(beta), epsilon_(epsilon), sigma_(sigma), - T_h_(T_h), T_add_(T_add), T_del_(T_del) { + width_(width), height_(height), size_(codebook_size + 1), + T_h_(T_h), T_add_(T_add), T_del_(T_del), + alpha_(alpha), beta_(beta), epsilon_(epsilon), sigma_(sigma) { cb_ = vector<Entry>(width * height * size_); for (size_t i = 0; i < cb_.size(); i += size_) { @@ -167,7 +167,7 @@ bool CBSegmentation::processPixel(CBSegmentation::Pixel &px, CBSegmentation::Cod // not found, create new codeword (to empty position or lru h or lfu m) // TODO: Should not prefer H codewords over M codewords? - if (size < (size_ - 1)) { + if ((size_t)size < (size_ - 1)) { entry = start + size; size++; entry->type = H; @@ -189,19 +189,19 @@ bool CBSegmentation::processPixel(CBSegmentation::Pixel &px, CBSegmentation::Cod } void CBSegmentation::apply(Mat &in, Mat &out) { - if ((out.rows != height_) || (out.cols != width_) + if (((size_t)out.rows != height_) || ((size_t)out.cols != width_) || (out.type() != CV_8UC1) || !out.isContinuous()) { out = Mat(height_, width_, CV_8UC1, cv::Scalar(0)); } // TODO: thread pool, queue N rows #pragma omp parallel for - for (int y = 0; y < height_; ++y) { + for (size_t y = 0; y < height_; ++y) { size_t idx = y * width_; uchar *ptr_in = in.ptr<uchar>(y); uchar *ptr_out = out.ptr<uchar>(y); - for (int x = 0; x < width_; ++x, ++idx, ptr_in += 3) { + for (size_t x = 0; x < width_; ++x, ++idx, ptr_in += 3) { auto px = Pixel(idx, ptr_in, 0, t_); if(processPixel(px)) { ptr_out[x] = 0; diff --git a/components/rgbd-sources/src/colour.cpp b/components/rgbd-sources/src/colour.cpp index 7168350b1..91c56797a 100644 --- a/components/rgbd-sources/src/colour.cpp +++ b/components/rgbd-sources/src/colour.cpp @@ -5,7 +5,7 @@ using std::vector; -static void gammaCorrection(const cv::Mat &img, const double gamma_){ +/*static void gammaCorrection(const cv::Mat &img, const double gamma_){ using namespace cv; Mat lookUpTable(1, 256, CV_8U); @@ -15,7 +15,7 @@ static void gammaCorrection(const cv::Mat &img, const double gamma_){ Mat res = img.clone(); LUT(img, lookUpTable, img); -} +}*/ static const std::vector<std::tuple<uchar,uchar,uchar>> kelvin_table = { {255,56,0}, // 1000 @@ -41,7 +41,7 @@ static const std::vector<std::tuple<uchar,uchar,uchar>> kelvin_table = { template <int C> inline float kelvinFactor(int temp) { int index = (temp / 500) - 2; - if (index >= kelvin_table.size()) index = kelvin_table.size(); + if (index >= (int)kelvin_table.size()) index = kelvin_table.size(); else if (index < 0) index = 0; return (float)std::get<C>(kelvin_table[index]) / 255.0f; } -- GitLab