From b3b0b9b3a1fcef58121c1ae96b99e2e394a5fd0b Mon Sep 17 00:00:00 2001 From: Matthew Powelson Date: Tue, 7 Jul 2020 14:49:35 -0500 Subject: [PATCH] Replace log4cxx with console_bridge --- mesh_segmenter/CMakeLists.txt | 5 +- mesh_segmenter/package.xml | 2 +- mesh_segmenter/src/mesh_segmenter.cpp | 30 +++----- noether/CMakeLists.txt | 12 +++- .../surface_raster_planner_application.cpp | 6 +- noether_examples/CMakeLists.txt | 15 ++-- path_sequence_planner/CMakeLists.txt | 5 +- path_sequence_planner/test/utest.cpp | 2 +- tool_path_planner/CMakeLists.txt | 6 +- .../raster_tool_path_planner.h | 5 -- .../src/raster_tool_path_planner.cpp | 68 ++++++++----------- tool_path_planner/test/utest.cpp | 9 ++- vtk_viewer/CMakeLists.txt | 5 +- vtk_viewer/cmake/vtk_viewer-config.cmake.in | 4 +- vtk_viewer/include/vtk_viewer/vtk_utils.h | 6 -- vtk_viewer/include/vtk_viewer/vtk_viewer.h | 2 - vtk_viewer/src/vtk_utils.cpp | 32 +++------ vtk_viewer/test/utest.cpp | 2 +- 18 files changed, 92 insertions(+), 124 deletions(-) diff --git a/mesh_segmenter/CMakeLists.txt b/mesh_segmenter/CMakeLists.txt index 292d41bf..f3c152c0 100644 --- a/mesh_segmenter/CMakeLists.txt +++ b/mesh_segmenter/CMakeLists.txt @@ -13,6 +13,7 @@ else() endif() find_package(catkin REQUIRED) +find_package(vtk_viewer REQUIRED) catkin_package( INCLUDE_DIRS @@ -21,6 +22,7 @@ catkin_package( ${PROJECT_NAME} DEPENDS VTK + vtk_viewer ) include_directories( @@ -34,6 +36,7 @@ add_library(${PROJECT_NAME} target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS} @@ -58,7 +61,7 @@ install(DIRECTORY include/${PROJECT_NAME}/ ## Testing ## ############# if(CATKIN_ENABLE_TESTING) - find_package(catkin REQUIRED COMPONENTS vtk_viewer) + find_package(vtk_viewer REQUIRED) include_directories( include ${catkin_INCLUDE_DIRS} diff --git a/mesh_segmenter/package.xml b/mesh_segmenter/package.xml index 6fe02259..e1284895 100644 --- a/mesh_segmenter/package.xml +++ b/mesh_segmenter/package.xml @@ -8,6 +8,6 @@ catkin - vtk_viewer + vtk_viewer diff --git a/mesh_segmenter/src/mesh_segmenter.cpp b/mesh_segmenter/src/mesh_segmenter.cpp index d9659467..97132b1b 100644 --- a/mesh_segmenter/src/mesh_segmenter.cpp +++ b/mesh_segmenter/src/mesh_segmenter.cpp @@ -12,24 +12,10 @@ #include -#include -#include -#include - -log4cxx::LoggerPtr createConsoleLogger(const std::string& logger_name) -{ - using namespace log4cxx; - PatternLayoutPtr pattern_layout(new PatternLayout("[\%-5p] [\%c](L:\%L): \%m\%n")); - ConsoleAppenderPtr console_appender(new ConsoleAppender(pattern_layout)); - log4cxx::LoggerPtr logger(Logger::getLogger(logger_name)); - logger->addAppender(console_appender); - logger->setLevel(Level::getInfo()); - return logger; -} +#include namespace mesh_segmenter { -static log4cxx::LoggerPtr SEGMENTATION_LOGGER = createConsoleLogger("SegmentationLogger"); void MeshSegmenter::setInputMesh(vtkSmartPointer mesh) { @@ -48,9 +34,9 @@ std::vector > MeshSegmenter::getMeshSegments() vtkSmartPointer input_copy = vtkSmartPointer::New(); input_copy->DeepCopy(input_mesh_); std::vector > meshes; - for (int i = 0; i < included_indices_.size(); ++i) + for (std::size_t i = 0; i < included_indices_.size(); ++i) { - LOG4CXX_INFO(SEGMENTATION_LOGGER, "Segment " << i << " size: " << included_indices_.at(i)->GetNumberOfIds()); + CONSOLE_BRIDGE_logInform(("Segment " + std::to_string(i) + " size: " + std::to_string(included_indices_.at(i)->GetNumberOfIds())).c_str()); vtkSmartPointer mesh = vtkSmartPointer::New(); // Create new pointer to a new copy of input_mesh_ @@ -72,7 +58,7 @@ std::vector > MeshSegmenter::getMeshSegments() if (mesh->GetNumberOfCells() <= 1) { - LOG4CXX_WARN(SEGMENTATION_LOGGER, "NOT ENOUGH CELLS FOR SEGMENTATION"); + CONSOLE_BRIDGE_logWarn("NOT ENOUGH CELLS FOR SEGMENTATION"); continue; } meshes.push_back(mesh); @@ -138,10 +124,10 @@ void MeshSegmenter::segmentMesh() } included_indices_.push_back(edge_cells); - LOG4CXX_INFO(SEGMENTATION_LOGGER, "Found " << included_indices_.size() << " segments"); - LOG4CXX_INFO(SEGMENTATION_LOGGER, "Total mesh size: " << size); - LOG4CXX_INFO(SEGMENTATION_LOGGER, "Used cells size: " << used_cells->GetNumberOfIds()); - LOG4CXX_INFO(SEGMENTATION_LOGGER, "Edge cells size: " << edge_cells->GetNumberOfIds()); + CONSOLE_BRIDGE_logInform("Found %d segments", included_indices_.size()); + CONSOLE_BRIDGE_logInform("Total mesh size: %d", size); + CONSOLE_BRIDGE_logInform("Used cells size: %d", used_cells->GetNumberOfIds()); + CONSOLE_BRIDGE_logInform("Edge cells size: %d", edge_cells->GetNumberOfIds()); } vtkSmartPointer MeshSegmenter::segmentMesh(int start_cell) diff --git a/noether/CMakeLists.txt b/noether/CMakeLists.txt index 413ae8e1..76947b96 100644 --- a/noether/CMakeLists.txt +++ b/noether/CMakeLists.txt @@ -31,9 +31,10 @@ find_package(catkin REQUIRED COMPONENTS pcl_conversions roscpp tool_path_planner - vtk_viewer ) +find_package(vtk_viewer REQUIRED) + find_package(noether_filtering) if(NOT noether_filtering_FOUND) message(WARNING "noether_filtering not found. mesh_filter_server will not be compiled") @@ -53,10 +54,10 @@ catkin_package( pcl_conversions roscpp tool_path_planner - vtk_viewer DEPENDS VTK PCL + vtk_viewer ) include_directories(include ${catkin_INCLUDE_DIRS}) @@ -68,6 +69,7 @@ add_executable(surface_raster_planner_server target_link_libraries(surface_raster_planner_server ${catkin_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) add_executable(surface_raster_planner_application @@ -76,6 +78,7 @@ add_executable(surface_raster_planner_application target_link_libraries(surface_raster_planner_application ${catkin_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) add_executable(segmentation_server @@ -84,6 +87,7 @@ add_executable(segmentation_server target_link_libraries(segmentation_server ${catkin_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) #There needs to be a better pathing to the library add_executable(convex_hull_node @@ -94,6 +98,7 @@ add_executable(convex_hull_node target_link_libraries(convex_hull_node ${catkin_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) if(noether_filtering_FOUND) @@ -103,6 +108,7 @@ if(noether_filtering_FOUND) target_link_libraries(mesh_filter_server PUBLIC ${catkin_LIBRARIES} noether_filtering::noether_filtering + noether::vtk_viewer ) endif() @@ -111,6 +117,7 @@ add_executable(edge_generator_server ) target_link_libraries(edge_generator_server ${catkin_LIBRARIES} + noether::vtk_viewer ) add_executable(halfedge_boundary_finder_server @@ -118,6 +125,7 @@ add_executable(halfedge_boundary_finder_server ) target_link_libraries(halfedge_boundary_finder_server ${catkin_LIBRARIES} + noether::vtk_viewer ) ############# diff --git a/noether/src/surface_raster_planner_application.cpp b/noether/src/surface_raster_planner_application.cpp index 15a2e502..4f461317 100644 --- a/noether/src/surface_raster_planner_application.cpp +++ b/noether/src/surface_raster_planner_application.cpp @@ -8,6 +8,7 @@ #include #include #include +#include namespace noether { @@ -148,7 +149,10 @@ int main(int argc, char **argv) pnh.param("centroid_y", center[1], 0.0); pnh.param("centroid_z", center[2], 0.0); - vtk_viewer::VTK_LOGGER->setLevel(console_debug_on ? log4cxx::Level::getDebug(): log4cxx::Level::getInfo()); + if (console_debug_on) + console_bridge::setLogLevel(console_bridge::LogLevel::CONSOLE_BRIDGE_LOG_DEBUG); + else + console_bridge::setLogLevel(console_bridge::LogLevel::CONSOLE_BRIDGE_LOG_INFO); // load tool config tool_path_planner::ProcessTool tool = loadTool(pnh); diff --git a/noether_examples/CMakeLists.txt b/noether_examples/CMakeLists.txt index 503c7e41..1355b455 100644 --- a/noether_examples/CMakeLists.txt +++ b/noether_examples/CMakeLists.txt @@ -32,9 +32,10 @@ find_package(catkin REQUIRED COMPONENTS roscpp roslib tool_path_planner - vtk_viewer ) +find_package(vtk_viewer REQUIRED) + catkin_package( INCLUDE_DIRS include @@ -48,10 +49,10 @@ catkin_package( roscpp roslib tool_path_planner - vtk_viewer DEPENDS VTK PCL + vtk_viewer ) include_directories( @@ -61,23 +62,23 @@ include_directories( ) add_executable(mesh_segmenter_client_node src/mesh_segmenter_client.cpp) -target_link_libraries(mesh_segmenter_client_node ${catkin_LIBRARIES} ${VTK_LIBRARIES}) +target_link_libraries(mesh_segmenter_client_node ${catkin_LIBRARIES} ${VTK_LIBRARIES} noether::vtk_viewer) list (APPEND PACKAGE_TARGETS mesh_segmenter_client_node) add_executable(mesh_segmenter_node src/mesh_segmenter_node.cpp) -target_link_libraries(mesh_segmenter_node ${catkin_LIBRARIES} ${VTK_LIBRARIES}) +target_link_libraries(mesh_segmenter_node ${catkin_LIBRARIES} ${VTK_LIBRARIES} noether::vtk_viewer) list (APPEND PACKAGE_TARGETS mesh_segmenter_node) add_executable(mesh_filtering_client src/mesh_filtering_client.cpp) -target_link_libraries(mesh_filtering_client ${catkin_LIBRARIES} ${PCL_LIBRARIES}) +target_link_libraries(mesh_filtering_client ${catkin_LIBRARIES} ${PCL_LIBRARIES} noether::vtk_viewer) list (APPEND PACKAGE_TARGETS mesh_filtering_client) add_executable(edge_generator_client src/edge_generator_client.cpp) -target_link_libraries(edge_generator_client ${catkin_LIBRARIES}) +target_link_libraries(edge_generator_client ${catkin_LIBRARIES} noether::vtk_viewer) list (APPEND PACKAGE_TARGETS edge_generator_client) add_executable(halfedge_finder_node src/halfedge_finder_node.cpp) -target_link_libraries(halfedge_finder_node ${catkin_LIBRARIES}) +target_link_libraries(halfedge_finder_node ${catkin_LIBRARIES} noether::vtk_viewer) list (APPEND PACKAGE_TARGETS halfedge_finder_node) ############# diff --git a/path_sequence_planner/CMakeLists.txt b/path_sequence_planner/CMakeLists.txt index 1b7ebca4..d7a964c2 100644 --- a/path_sequence_planner/CMakeLists.txt +++ b/path_sequence_planner/CMakeLists.txt @@ -15,9 +15,10 @@ endif() find_package(catkin REQUIRED COMPONENTS tool_path_planner - vtk_viewer ) +find_package(vtk_viewer REQUIRED) + catkin_package( INCLUDE_DIRS include @@ -25,6 +26,7 @@ catkin_package( simple_path_sequence_planner CATKIN_DEPENDS tool_path_planner + DEPENDS vtk_viewer ) @@ -39,6 +41,7 @@ add_library(simple_path_sequence_planner target_link_libraries(simple_path_sequence_planner ${catkin_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) ############# diff --git a/path_sequence_planner/test/utest.cpp b/path_sequence_planner/test/utest.cpp index cf17cd9b..b26461d6 100644 --- a/path_sequence_planner/test/utest.cpp +++ b/path_sequence_planner/test/utest.cpp @@ -148,7 +148,7 @@ TEST(IntersectTest, TestCase1) #ifdef NDEBUG // release build stuff goes here - LOG4CXX_ERROR(vtk_viewer::VTK_LOGGER,"noether/path_sequence_planner test: visualization is only available in debug mode"); + CONSOLE_BRIDGE_logError("noether/path_sequence_planner test: visualization is only available in debug mode"); #else // Debug-specific code goes here viz.renderDisplay(); diff --git a/tool_path_planner/CMakeLists.txt b/tool_path_planner/CMakeLists.txt index dcdd3c57..67eb7c5e 100644 --- a/tool_path_planner/CMakeLists.txt +++ b/tool_path_planner/CMakeLists.txt @@ -15,9 +15,10 @@ find_package(catkin REQUIRED COMPONENTS rosconsole roslib shape_msgs - vtk_viewer ) +find_package(vtk_viewer REQUIRED) + find_package(VTK REQUIRED NO_MODULE) if(VTK_FOUND AND ("${VTK_VERSION}" VERSION_LESS 7.1)) message(FATAL_ERROR "The minimum required version of VTK is 7.1, but found ${VTK_VERSION}") @@ -47,11 +48,11 @@ catkin_package( noether_msgs rosconsole shape_msgs - vtk_viewer DEPENDS EIGEN3 PCL VTK + vtk_viewer ) include_directories( @@ -71,6 +72,7 @@ target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${VTK_LIBRARIES} + noether::vtk_viewer ) add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS} diff --git a/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h b/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h index d52bf865..3a35a9b0 100644 --- a/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h +++ b/tool_path_planner/include/tool_path_planner/raster_tool_path_planner.h @@ -29,8 +29,6 @@ #include #include #include -#include -#include #include #include "tool_path_planner/tool_path_planner_base.h" @@ -39,9 +37,6 @@ namespace tool_path_planner class RasterToolPathPlanner : public ToolPathPlannerBase { public: - - static log4cxx::LoggerPtr RASTER_PATH_PLANNER_LOGGER; - /** * @brief constructor * @param use_ransac set flag to use ransac plane estimation to determine path normals diff --git a/tool_path_planner/src/raster_tool_path_planner.cpp b/tool_path_planner/src/raster_tool_path_planner.cpp index c23e2389..f444962c 100644 --- a/tool_path_planner/src/raster_tool_path_planner.cpp +++ b/tool_path_planner/src/raster_tool_path_planner.cpp @@ -33,9 +33,8 @@ #include #include -#include -#include -#include +#include + #include #include "tool_path_planner/utilities.h" @@ -45,19 +44,6 @@ static const double ANGLE_CORRECTION_THRESHOLD = (150.0/180.0)*M_PI; static const double EXTRUDE_EXTEND_PERCENTAGE = 1.5; static const double RAY_INTERSECTION_TOLERANCE = 0.001; -log4cxx::LoggerPtr createConsoleLogger(const std::string& logger_name) -{ - using namespace log4cxx; - PatternLayoutPtr pattern_layout(new PatternLayout( "[\%-5p] [\%c](L:\%L): \%m\%n")); - ConsoleAppenderPtr console_appender(new ConsoleAppender(pattern_layout)); - log4cxx::LoggerPtr logger(Logger::getLogger(logger_name)); - logger->addAppender(console_appender); - logger->setLevel(Level::getInfo()); - return logger; -} -log4cxx::LoggerPtr tool_path_planner::RasterToolPathPlanner::RASTER_PATH_PLANNER_LOGGER = createConsoleLogger( - "RasterPathPlanner"); - /** * @brief computes the angle between two vectors * @param v1 @@ -144,7 +130,7 @@ namespace tool_path_planner planPaths(meshes[i], new_path); if(new_path.empty()) { - LOG4CXX_WARN(RASTER_PATH_PLANNER_LOGGER, "Could not plan path for mesh " << i); + CONSOLE_BRIDGE_logWarn("Could not plan path for mesh %d", i); } else { @@ -278,7 +264,7 @@ namespace tool_path_planner // if paths need to be modified, delete all old paths (starting at the back) and insert new ones if(!delete_paths.empty()) { - LOG4CXX_INFO(RASTER_PATH_PLANNER_LOGGER, "Deleting " << delete_paths.size() << " paths"); + CONSOLE_BRIDGE_logInform("Deleting %d paths", delete_paths.size()); } for(int i = delete_paths.size() - 1; i >=0 ; --i ) { @@ -297,7 +283,7 @@ namespace tool_path_planner sum_of_normal += current_normal; } sum_of_normal.normalize(); // this is now the average normal - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"Line Normal = \n" << sum_of_normal); + CONSOLE_BRIDGE_logDebug("Line Normal = %d", sum_of_normal); vtkDataArray* normals = new_paths[i].line->GetPointData()->GetNormals(); // flip normal directions if it is in a different direction from the average of normal for the line @@ -309,10 +295,10 @@ namespace tool_path_planner Eigen::Vector3d current_normal = Eigen::Vector3d::Zero(); new_paths[i].line->GetPointData()->GetNormals()->GetTuple(j,current_normal.data()); double dp = current_normal.dot(sum_of_normal); - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"Line " << i <<" waypoint "<< j << " dot product: " << dp); + CONSOLE_BRIDGE_logDebug("Line %d waypoint %d dot product: %d", i, j, dp); if(dp < 0) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"Flipping line " << i <<" waypoint "<< j); + CONSOLE_BRIDGE_logDebug("Flipping line %d waypoint $d", i, j); double* pt = line_normals ->GetTuple(i); pt[0] *= -1; pt[1] *= -1; @@ -354,7 +340,7 @@ namespace tool_path_planner } else { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, "Failed to generate path off leading edge"); + CONSOLE_BRIDGE_logError("Failed to generate path off leading edge"); } if (getExtraPath(last, last_path, tool_.line_spacing)) { @@ -362,7 +348,7 @@ namespace tool_path_planner } else { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, "Failed to generate path off trailing edge"); + CONSOLE_BRIDGE_logError("Failed to generate path off trailing edge"); } } @@ -411,7 +397,7 @@ namespace tool_path_planner if(!findIntersectionLine(cutting_mesh, intersection_line, spline)) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"No intersection found"); + CONSOLE_BRIDGE_logDebug("No intersection found"); return false; } @@ -434,7 +420,7 @@ namespace tool_path_planner { if(dist == 0.0 && this_path.intersection_plane->GetPoints()->GetNumberOfPoints() < 2) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"No path offset and no intersection plane given. Cannot generate next path"); + CONSOLE_BRIDGE_logDebug("No path offset and no intersection plane given. Cannot generate next path"); return false; } @@ -492,7 +478,7 @@ namespace tool_path_planner if(!findIntersectionLine(next_path.intersection_plane, intersection_line, spline)) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"No intersection found for creating spline"); + CONSOLE_BRIDGE_logDebug("No intersection found for creating spline"); return false; } @@ -509,7 +495,7 @@ namespace tool_path_planner intersection_filter->Update(); if(intersection_filter->GetOutput()->GetPoints()->GetNumberOfPoints() > 0) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"Self intersection found with back path"); + CONSOLE_BRIDGE_logDebug("Self intersection found with back path"); return false; } @@ -517,7 +503,7 @@ namespace tool_path_planner intersection_filter->Update(); if(intersection_filter->GetOutput()->GetPoints()->GetNumberOfPoints() > 0) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER, "Self intersection found with front path"); + CONSOLE_BRIDGE_logDebug("Self intersection found with front path"); return false; } } @@ -554,7 +540,7 @@ namespace tool_path_planner if(points->GetPoints()->GetNumberOfPoints() < 2) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"Number of points after smoothing is less than 2, skip computing path data"); + CONSOLE_BRIDGE_logDebug("Number of points after smoothing is less than 2, skip computing path data"); return false; } next_path.line = points; @@ -587,7 +573,7 @@ namespace tool_path_planner { if (std::fabs(dist) == 0.0) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, "No offset given. Cannot generate extra path"); + CONSOLE_BRIDGE_logError("No offset given. Cannot generate extra path"); return false; } @@ -711,7 +697,7 @@ namespace tool_path_planner } else { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"Hole segment has less than 2 points, skipping resampling"); + CONSOLE_BRIDGE_logDebug("Hole segment has less than 2 points, skipping resampling"); } new_line->SetPoints(new_points); @@ -938,8 +924,7 @@ namespace tool_path_planner // Check to make sure that the input cut surface contains a valid mesh if(cut_surface->GetNumberOfCells() < 1) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, - "Number of input cells for calculating intersection is less than 1, cannot compute intersection"); + CONSOLE_BRIDGE_logError("Number of input cells for calculating intersection is less than 1, cannot compute intersection"); return false; } @@ -977,7 +962,7 @@ namespace tool_path_planner if(temp_pts->GetNumberOfPoints() == 0) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER, "No connected lines were found"); + CONSOLE_BRIDGE_logError("No connected lines were found"); return false; } @@ -1470,7 +1455,7 @@ namespace tool_path_planner cell_locator_->FindClosestPoint(query_point.data(),closest_point.data(),cell_id,sub_index,dist); if(cell_id < 0) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER,"FindClosestPoint returned an invalid cell id"); + CONSOLE_BRIDGE_logError("FindClosestPoint returned an invalid cell id"); return false; } @@ -1495,13 +1480,13 @@ namespace tool_path_planner // If normal or derivative data does not exist, or number of normals and derivatives do not match, return a null pointer if(!normals || !ders || normals->GetNumberOfTuples() != ders->GetNumberOfTuples()) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER,"Could not create offset line"); + CONSOLE_BRIDGE_logError("Could not create offset line"); return new_points; } if(normals->GetNumberOfTuples() != line->GetNumberOfPoints()) { - LOG4CXX_DEBUG(RASTER_PATH_PLANNER_LOGGER,"ERROR IN CALC OFFSET LINE"); + CONSOLE_BRIDGE_logDebug("ERROR IN CALC OFFSET LINE"); return new_points; } @@ -1588,7 +1573,7 @@ namespace tool_path_planner if(!normals) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER,"no normals, cannot create surface from spline"); + CONSOLE_BRIDGE_logError("No normals, cannot create surface from spline"); return new_surface; } @@ -1676,7 +1661,7 @@ namespace tool_path_planner if(!normals) { - LOG4CXX_ERROR(RASTER_PATH_PLANNER_LOGGER,"no normals, cannot create surface from spline"); + CONSOLE_BRIDGE_logError("No normals, cannot create surface from spline"); return new_surface; } @@ -1735,7 +1720,10 @@ namespace tool_path_planner void RasterToolPathPlanner::enableConsoleDebug(bool enable) { - RASTER_PATH_PLANNER_LOGGER->setLevel(enable ? log4cxx::Level::getDebug() : log4cxx::Level::getInfo()); + if (enable) + console_bridge::setLogLevel(console_bridge::LogLevel::CONSOLE_BRIDGE_LOG_DEBUG); + else + console_bridge::setLogLevel(console_bridge::LogLevel::CONSOLE_BRIDGE_LOG_INFO); } } diff --git a/tool_path_planner/test/utest.cpp b/tool_path_planner/test/utest.cpp index 138838dd..a594b4a6 100644 --- a/tool_path_planner/test/utest.cpp +++ b/tool_path_planner/test/utest.cpp @@ -115,8 +115,7 @@ TEST(IntersectTest, RasterRotationTest) #ifdef NDEBUG // release build stuff goes here - LOG4CXX_ERROR(tool_path_planner::RasterToolPathPlanner::RASTER_PATH_PLANNER_LOGGER, - "noether/tool_path_planner test: visualization is only available in debug mode"); + CONSOLE_BRIDGE_logError("noether/tool_path_planner test: visualization is only available in debug mode"); #else // Debug-specific code goes here viz.renderDisplay(); @@ -224,7 +223,7 @@ TEST(IntersectTest, TestCase1) #ifdef NDEBUG // release build stuff goes here - LOG4CXX_ERROR(tool_path_planner::RasterToolPathPlanner::RASTER_PATH_PLANNER_LOGGER, "noether/tool_path_planner test: visualization is only available in debug mode"); + CONSOLE_BRIDGE_logError("noether/tool_path_planner test: visualization is only available in debug mode"); #else // Debug-specific code goes here viz.renderDisplay(); @@ -325,7 +324,7 @@ TEST(IntersectTest, TestCaseRansac) #ifdef NDEBUG // release build stuff goes here - LOG4CXX_ERROR(tool_path_planner::RasterToolPathPlanner::RASTER_PATH_PLANNER_LOGGER, "noether/tool_path_planner test: visualization is only available in debug mode"); + CONSOLE_BRIDGE_logError("noether/tool_path_planner test: visualization is only available in debug mode"); #else // Debug-specific code goes here viz.renderDisplay(); @@ -393,7 +392,7 @@ TEST(IntersectTest, ExtraRasterTest) #ifdef NDEBUG // release build stuff goes here - LOG4CXX_INFO(tool_path_planner::RasterToolPathPlanner::RASTER_PATH_PLANNER_LOGGER, "noether/tool_path_planner test: visualization is only available in debug mode"); + CONSOLE_BRIDGE_logInform("noether/tool_path_planner test: visualization is only available in debug mode"); #else // Debug-specific code goes here diff --git a/vtk_viewer/CMakeLists.txt b/vtk_viewer/CMakeLists.txt index cd3850e2..60ede11c 100644 --- a/vtk_viewer/CMakeLists.txt +++ b/vtk_viewer/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.5.0) project(vtk_viewer VERSION 0.1.0) -find_package(cmake_common_scripts REQUIRED 0.1) +find_package(cmake_common_scripts REQUIRED) find_package(VTK REQUIRED NO_MODULE) if(VTK_FOUND AND ("${VTK_VERSION}" VERSION_LESS 7.1)) @@ -18,11 +18,12 @@ else() endif() find_package(Eigen3 REQUIRED) +find_package(console_bridge REQUIRED) add_code_coverage() add_library(${PROJECT_NAME} SHARED src/mouse_interactor.cpp src/vtk_utils.cpp src/${PROJECT_NAME}.cpp) -target_link_libraries(${PROJECT_NAME} PUBLIC ${PCL_LIBRARIES} ${VTK_LIBRARIES}) +target_link_libraries(${PROJECT_NAME} PUBLIC ${PCL_LIBRARIES} ${VTK_LIBRARIES} console_bridge) target_include_directories(${PROJECT_NAME} PUBLIC "$" "$") diff --git a/vtk_viewer/cmake/vtk_viewer-config.cmake.in b/vtk_viewer/cmake/vtk_viewer-config.cmake.in index 385b1845..5bea2682 100644 --- a/vtk_viewer/cmake/vtk_viewer-config.cmake.in +++ b/vtk_viewer/cmake/vtk_viewer-config.cmake.in @@ -5,9 +5,9 @@ set_and_check(@PROJECT_NAME@_INCLUDE_DIRS "${PACKAGE_PREFIX_DIR}/include") set_and_check(@PROJECT_NAME@_LIBRARIES "${PACKAGE_PREFIX_DIR}/lib") include(CMakeFindDependencyMacro) -find_dependency(cmake_common_scripts 0.1) +find_dependency(cmake_common_scripts) +find_dependency(console_bridge) find_dependency(PCL 1.9) find_dependency(VTK 7.1) -find_dependency(console_bridge) include("${CMAKE_CURRENT_LIST_DIR}/@PROJECT_NAME@-targets.cmake") diff --git a/vtk_viewer/include/vtk_viewer/vtk_utils.h b/vtk_viewer/include/vtk_viewer/vtk_utils.h index 3940346e..98bec731 100644 --- a/vtk_viewer/include/vtk_viewer/vtk_utils.h +++ b/vtk_viewer/include/vtk_viewer/vtk_utils.h @@ -30,14 +30,8 @@ #include #include -#include - namespace vtk_viewer { - - - extern log4cxx::LoggerPtr VTK_LOGGER; - /** * @brief Enum used to define the type of plane generated by createPlane */ diff --git a/vtk_viewer/include/vtk_viewer/vtk_viewer.h b/vtk_viewer/include/vtk_viewer/vtk_viewer.h index 483a6174..805d2c09 100644 --- a/vtk_viewer/include/vtk_viewer/vtk_viewer.h +++ b/vtk_viewer/include/vtk_viewer/vtk_viewer.h @@ -32,8 +32,6 @@ namespace vtk_viewer { - - class VTKViewer { public: diff --git a/vtk_viewer/src/vtk_utils.cpp b/vtk_viewer/src/vtk_utils.cpp index 783e75ec..dd0e2932 100644 --- a/vtk_viewer/src/vtk_utils.cpp +++ b/vtk_viewer/src/vtk_utils.cpp @@ -49,24 +49,10 @@ #include #include -#include -#include -#include - -log4cxx::LoggerPtr createConsoleLogger(const std::string& logger_name) -{ - using namespace log4cxx; - PatternLayoutPtr pattern_layout(new PatternLayout("[\%-5p] [\%c](L:\%L): \%m\%n")); // NOLINT - ConsoleAppenderPtr console_appender(new ConsoleAppender(pattern_layout)); - log4cxx::LoggerPtr logger(Logger::getLogger(logger_name)); - logger->addAppender(console_appender); - logger->setLevel(Level::getInfo()); - return logger; -} +#include namespace vtk_viewer { -log4cxx::LoggerPtr VTK_LOGGER = createConsoleLogger("VTK_VIEWER"); vtkSmartPointer createPlane(unsigned int grid_size_x, unsigned int grid_size_y, vtk_viewer::plane_type type) { @@ -398,7 +384,7 @@ vtkSmartPointer estimateCurvature(vtkSmartPointer mesh bool embedRightHandRuleNormals(vtkSmartPointer& data) { bool success = true; - LOG4CXX_DEBUG(VTK_LOGGER, "Embedding mesh normals from right hand rule"); + CONSOLE_BRIDGE_logDebug("Embedding mesh normals from right hand rule"); int size = static_cast(data->GetNumberOfCells()); vtkDoubleArray* cell_normals = vtkDoubleArray::New(); @@ -476,7 +462,7 @@ bool embedRightHandRuleNormals(vtkSmartPointer& data) } } if (bad_cells > 0) - LOG4CXX_ERROR(VTK_LOGGER, "Could not embed normals on " << bad_cells << "cells"); + CONSOLE_BRIDGE_logError("Could not embed normals on %d cells", bad_cells); // We have looped over every cell. Now embed the normals data->GetCellData()->SetNormals(cell_normals); @@ -488,7 +474,7 @@ void generateNormals(vtkSmartPointer& data, int flip_normals) // If point data exists but cell data does not, iterate through the cells and generate normals manually if (data->GetPointData()->GetNormals() && !data->GetCellData()->GetNormals()) { - LOG4CXX_DEBUG(VTK_LOGGER, "Generating Mesh Normals manually"); + CONSOLE_BRIDGE_logDebug("Generating Mesh Normals manually"); int size = static_cast(data->GetNumberOfCells()); vtkDoubleArray* cell_normals = vtkDoubleArray::New(); @@ -531,7 +517,7 @@ void generateNormals(vtkSmartPointer& data, int flip_normals) } else { - LOG4CXX_DEBUG(VTK_LOGGER, "Recomputing Mesh normals"); + CONSOLE_BRIDGE_logDebug("Recomputing Mesh normals"); vtkSmartPointer normal_generator = vtkSmartPointer::New(); normal_generator->SetInputData(data); normal_generator->ComputePointNormalsOn(); @@ -546,23 +532,23 @@ void generateNormals(vtkSmartPointer& data, int flip_normals) if (!data->GetPointData()->GetNormals()) { normal_generator->SetComputePointNormals(1); - LOG4CXX_DEBUG(VTK_LOGGER, "Point Normals Computation ON"); + CONSOLE_BRIDGE_logDebug("Point Normals Computation ON"); } else { normal_generator->SetComputePointNormals(0); - LOG4CXX_DEBUG(VTK_LOGGER, "Point Normals Computation OFF"); + CONSOLE_BRIDGE_logDebug("Point Normals Computation OFF"); } if (!data->GetCellData()->GetNormals()) { normal_generator->SetComputeCellNormals(1); - LOG4CXX_DEBUG(VTK_LOGGER, "Cell Normals Computation ON"); + CONSOLE_BRIDGE_logDebug("Cell Normals Computation ON"); } else { normal_generator->SetComputeCellNormals(0); - LOG4CXX_DEBUG(VTK_LOGGER, "Cell Normals Computation OFF"); + CONSOLE_BRIDGE_logDebug("Cell Normals Computation OFF"); } normal_generator->SetFlipNormals(0); diff --git a/vtk_viewer/test/utest.cpp b/vtk_viewer/test/utest.cpp index 55e709c1..ed72e9ae 100644 --- a/vtk_viewer/test/utest.cpp +++ b/vtk_viewer/test/utest.cpp @@ -67,7 +67,7 @@ TEST(ViewerTest, TestCase1) #ifdef NDEBUG // release build stuff goes here - LOG4CXX_ERROR(vtk_viewer::VTK_LOGGER,"noether/vtk_viewer: visualization is only available in debug mode"); + CONSOLE_BRIDGE_logError("noether/vtk_viewer: visualization is only available in debug mode"); #else // Debug-specific code goes here viz.renderDisplay();