diff --git a/.travis.yml b/.travis.yml
index ad108164..96a94e52 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -11,6 +11,8 @@ env:
global:
- NOT_TEST_BUILD=true
- UPSTREAM_WORKSPACE='dependencies_ros1.rosinstall'
+ - ROSDEP_SKIP_KEYS='iwyu cmake_common_scripts'
+ - ADDITIONAL_DEBS='iwyu'
matrix:
include:
diff --git a/dependencies_ros1.rosinstall b/dependencies_ros1.rosinstall
index ce8894c1..564833af 100644
--- a/dependencies_ros1.rosinstall
+++ b/dependencies_ros1.rosinstall
@@ -1,2 +1,3 @@
# PCL ros tools, this is required because using custom version of PCL and VTK
- git: {local-name: perception_pcl, uri: 'https://github.com/ros-perception/perception_pcl.git', version: 1.7.1}
+- git: {local-name: cmake_common_scripts, uri: 'https://github.com/ros-industrial/cmake_common_scripts.git', version: master}
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/noether_filtering/package.xml b/noether_filtering/package.xml
index 2ae74699..2fb776b2 100644
--- a/noether_filtering/package.xml
+++ b/noether_filtering/package.xml
@@ -7,7 +7,7 @@
Apache 2.0
Jorge Nicho
- catkin
+ libconsole-bridge-dev
pluginlib
libpcl-all-dev
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 7e0b9e0f..271415fa 100644
--- a/vtk_viewer/CMakeLists.txt
+++ b/vtk_viewer/CMakeLists.txt
@@ -1,23 +1,13 @@
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 3.5.0)
+project(vtk_viewer VERSION 0.1.0)
-## Compile as C++14,
-add_compile_options(-std=c++14)
-
-project(vtk_viewer)
-
-find_package(catkin REQUIRED COMPONENTS
- cmake_modules
- rosconsole
-)
+find_package(cmake_common_scripts 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}")
set(VTK_FOUND FALSE)
endif()
-#else()
-# include(${VTK_USE_FILE})
-#endif()
find_package(PCL REQUIRED)
if(PCL_FOUND AND ("${PCL_VERSION}" VERSION_LESS 1.9))
@@ -28,54 +18,40 @@ else()
endif()
find_package(Eigen3 REQUIRED)
+find_package(console_bridge REQUIRED)
-catkin_package(
- INCLUDE_DIRS
- include
- LIBRARIES
- ${PROJECT_NAME}
- DEPENDS
- EIGEN3
- PCL
- VTK
-)
-
-include_directories(
- include
- ${catkin_INCLUDE_DIRS}
- ${EIGEN3_INCLUDE_DIRS}
- ${PCL_INCLUDE_DIRS}
-)
-
-add_library(${PROJECT_NAME}
- src/mouse_interactor.cpp
- src/vtk_utils.cpp
- src/${PROJECT_NAME}.cpp
-)
-target_link_libraries(${PROJECT_NAME}
- ${catkin_LIBRARIES}
- ${PCL_LIBRARIES}
- ${VTK_LIBRARIES}
-)
-
-install(TARGETS ${PROJECT_NAME}
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-)
+if(NOETHER_ENABLE_TESTING)
+ set(CLANG_ARGS ${DEFAULT_CLANG_TIDY_ERROR_ARGS})
+else()
+ set(CLANG_ARGS ${DEFAULT_CLANG_TIDY_WARNING_ARGS})
+endif()
-install(DIRECTORY include/${PROJECT_NAME}/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+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} console_bridge)
+target_include_directories(${PROJECT_NAME} PUBLIC
+ "$"
+ "$")
+target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC
+ ${EIGEN3_INCLUDE_DIRS}
+ ${PCL_INCLUDE_DIRS})
+target_cxx_version(${PROJECT_NAME} PUBLIC VERSION 14)
+target_clang_tidy(${PROJECT_NAME} ARGUMENTS ${CLANG_ARGS} ENABLE ${NOETHER_ENABLE_TESTING})
+target_include_what_you_use(${PROJECT_NAME} ARGUMENTS ${DEFAULT_IWYU_ARGS} ENABLE ${NOETHER_ENABLE_TESTING})
+target_cppcheck(${PROJECT_NAME} ARGUMENTS ${DEFAULT_CPPCHECK_ARGS} ENABLE ${NOETHER_ENABLE_TESTING})
+
+configure_package(NAMESPACE noether TARGETS ${PROJECT_NAME})
+
+# Mark header files for installation
+install(DIRECTORY include/${PROJECT_NAME}
+ DESTINATION include
+ FILES_MATCHING PATTERN "*.h"
PATTERN ".svn" EXCLUDE
)
-if (CATKIN_ENABLE_TESTING)
- catkin_add_gtest(${PROJECT_NAME}-test
- test/utest.cpp
- )
- if(TARGET ${PROJECT_NAME}-test)
- target_link_libraries(${PROJECT_NAME}-test
- ${PROJECT_NAME}
- )
- endif()
+if (NOETHER_ENABLE_TESTING)
+ enable_testing()
+ add_run_tests_target()
+ add_subdirectory(test)
endif()
diff --git a/vtk_viewer/cmake/vtk_viewer-config.cmake.in b/vtk_viewer/cmake/vtk_viewer-config.cmake.in
new file mode 100644
index 00000000..0a334cef
--- /dev/null
+++ b/vtk_viewer/cmake/vtk_viewer-config.cmake.in
@@ -0,0 +1,12 @@
+@PACKAGE_INIT@
+
+set(@PROJECT_NAME@_FOUND ON)
+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(console_bridge)
+find_dependency(PCL)
+find_dependency(VTK)
+
+include("${CMAKE_CURRENT_LIST_DIR}/@PROJECT_NAME@-targets.cmake")
diff --git a/vtk_viewer/include/vtk_viewer/mouse_interactor.h b/vtk_viewer/include/vtk_viewer/mouse_interactor.h
index 3e7e2524..b100e7f8 100644
--- a/vtk_viewer/include/vtk_viewer/mouse_interactor.h
+++ b/vtk_viewer/include/vtk_viewer/mouse_interactor.h
@@ -54,7 +54,7 @@ class MouseInteractorStyle : public vtkInteractorStyleTrackballCamera
* @brief getSaveLocation Get the current pathway used to save polydata to
* @return The current pathway for saving data
*/
- std::string getSaveLocation(){return save_location_.str().c_str();}
+ std::string getSaveLocation(){return save_location_.str();}
/**
* @brief OnLeftButtonDown Callback function for handling left mouse button click events, selects an actor in a window
diff --git a/vtk_viewer/include/vtk_viewer/vtk_utils.h b/vtk_viewer/include/vtk_viewer/vtk_utils.h
index 8421b86b..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
*/
@@ -73,7 +67,7 @@ namespace vtk_viewer
* @param neighborhood_size The number of points to consider for determining cell size and orientation
* @return The mesh object after triangulation
*/
- vtkSmartPointer createMesh(vtkSmartPointer points, double sample_spacing, double neigborhood_size);
+ vtkSmartPointer createMesh(vtkSmartPointer points, double sample_spacing, int neigborhood_size);
/**
* @brief cleanMesh Given a mesh, removes cells that do not have enough point data nearby (called after createMesh)
@@ -126,7 +120,7 @@ namespace vtk_viewer
* @param file The input file to load
* @param polydata [output] The VTK object to return
* @param background Optional point cloud to be used to perform background subtraction
- * @param return_mesh If true, computes and returns a mesh, if false, will only return the point data
+ * @param return_mesh [currently unused] If true, computes and returns a mesh, if false, will only return the point data
* @return True if the file exists and was loaded, False if there was an error
*/
bool loadPCDFile(std::string file, vtkSmartPointer& polydata, std::string background = "", bool return_mesh = true);
diff --git a/vtk_viewer/include/vtk_viewer/vtk_viewer.h b/vtk_viewer/include/vtk_viewer/vtk_viewer.h
index 1a816baa..48434560 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:
@@ -48,7 +46,7 @@ namespace vtk_viewer
* @param polydata The polydata to be displayed
* @param color The color to use for rendering the data
*/
- void addPolyDataDisplay(vtkPolyData* polydata, std::vector color);
+ void addPolyDataDisplay(vtkPolyData* polydata, const std::vector& color);
/**
* @brief addPolyNormalsDisplay Add a renderer and actor for a polydata
@@ -57,14 +55,14 @@ namespace vtk_viewer
* @param color The color to use for rendering the data
* @param scale The size to scale and show the arrows at
*/
- void addPolyNormalsDisplay(vtkPolyData* polydata, std::vector color, double scale);
+ void addPolyNormalsDisplay(vtkPolyData* polydata, const std::vector& color, double scale);
/**
* @brief addPointDataDisplay Add a renderer and actor for a point data object
* @param points The point data to be displayed
* @param color The color to use for rendering the data
*/
- void addPointDataDisplay(vtkPoints* points, std::vector color);
+ void addPointDataDisplay(vtkPoints* points, const std::vector& color);
/**
* @brief addCellNormalDisplay Displays the normals for a mesh object
@@ -72,7 +70,7 @@ namespace vtk_viewer
* @param color The color to use for rendering the data
* @param scale The size to scale and show the arrows at
*/
- void addCellNormalDisplay(vtkPolyData* polydata, std::vector color, double scale);
+ void addCellNormalDisplay(vtkPolyData* polydata, const std::vector& color, double scale);
/**
* @brief renderDisplay Calls the VTK window Render() command to visualize
@@ -85,7 +83,7 @@ namespace vtk_viewer
* objects currently being displayed
* @return The number of actor objects
*/
- int getNumberOfDisplayObjects(){return actors_.size();}
+ std::size_t getNumberOfDisplayObjects(){return actors_.size();}
/**
* @brief removeObjectDisplay Remove an object from the list of objects
@@ -94,7 +92,7 @@ namespace vtk_viewer
* @return True if the index of the item to remove exists and was removed,
* false if the index exceeds the list of items available
*/
- bool removeObjectDisplay(int index);
+ bool removeObjectDisplay(std::size_t index);
/**
* @brief removeAllDisplays Removes all displays from the renderer
diff --git a/vtk_viewer/package.xml b/vtk_viewer/package.xml
index 657ef455..fdc6a5ee 100644
--- a/vtk_viewer/package.xml
+++ b/vtk_viewer/package.xml
@@ -7,8 +7,8 @@
Apache 2.0
catkin
- cmake_modules
- rosconsole
+ cmake_common_scripts
+ libconsole-bridge-dev
libpcl-all-dev
rosunit
diff --git a/vtk_viewer/src/vtk_utils.cpp b/vtk_viewer/src/vtk_utils.cpp
index a7685ed1..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"));
- 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)
{
@@ -102,7 +88,7 @@ vtkSmartPointer createPlane(unsigned int grid_size_x, unsigned int gr
vtkSmartPointer createMesh(vtkSmartPointer points,
double sample_spacing,
- double neigborhood_size)
+ int neigborhood_size)
{
if (!points)
{
@@ -148,7 +134,8 @@ void cleanMesh(const vtkSmartPointer& points, vtkSmartPointerBuildLocator();
vtkSmartPointer cells = mesh->GetPolys();
- int size = cells->GetNumberOfCells();
+ assert(cells->GetNumberOfCells() < std::numeric_limits::max());
+ int size = static_cast(cells->GetNumberOfCells());
// loop through all cells, mark cells for deletion if they do not have enough points nearby
for (int i = 0; i < size; ++i)
{
@@ -234,7 +221,7 @@ vtkSmartPointer readSTLFile(std::string file)
return reader->GetOutput();
}
-bool loadPCDFile(std::string file, vtkSmartPointer& polydata, std::string background, bool return_mesh)
+bool loadPCDFile(std::string file, vtkSmartPointer& polydata, std::string background, bool /*return_mesh*/)
{
pcl::PointCloud::Ptr cloud(new pcl::PointCloud);
@@ -277,7 +264,7 @@ void vtkSurfaceReconstructionMesh(const pcl::PointCloud::Ptr clou
// Set parameters (TODO: Make these parameters configurable)
mls.setComputeNormals(false);
mls.setInputCloud(cloud);
- mls.setPolynomialFit(true);
+ mls.setPolynomialOrder(2);
mls.setSearchMethod(tree);
mls.setSearchRadius(0.01);
@@ -304,10 +291,10 @@ void removeBackground(pcl::PointCloud& cloud, const pcl::PointClo
return;
}
- for (int i = 0; i < cloud.points.size(); ++i)
+ for (std::size_t i = 0; i < cloud.points.size(); ++i)
{
- if (fabs(cloud.points[i].z - background.points[i].z) < 0.05 || std::isnan(background.points[i].z) ||
- cloud.points[i].y > 0.75)
+ if (fabs(cloud.points[i].z - background.points[i].z) < 0.05f || std::isnan(background.points[i].z) ||
+ cloud.points[i].y > 0.75f)
{
cloud.points[i].x = NAN;
cloud.points[i].y = NAN;
@@ -317,7 +304,7 @@ void removeBackground(pcl::PointCloud& cloud, const pcl::PointClo
// create new point cloud with NaN's removed
pcl::PointCloud cloud2;
- for (int i = 0; i < cloud.points.size(); ++i)
+ for (std::size_t i = 0; i < cloud.points.size(); ++i)
{
if (!std::isnan(cloud.points[i].x))
{
@@ -334,7 +321,7 @@ void removeBackground(pcl::PointCloud& cloud, const pcl::PointClo
void PCLtoVTK(const pcl::PointCloud& cloud, vtkPolyData* const pdata)
{
vtkSmartPointer points = vtkSmartPointer::New();
- for (int i = 0; i < cloud.points.size(); ++i)
+ for (std::size_t i = 0; i < cloud.points.size(); ++i)
{
if (std::isnan(cloud.points[i].x) || std::isnan(cloud.points[i].y) || std::isnan(cloud.points[i].z))
{
@@ -353,18 +340,18 @@ void PCLtoVTK(const pcl::PointCloud& cloud, vtkPolyData* const pd
void VTKtoPCL(vtkPolyData* const pdata, pcl::PointCloud& cloud)
{
- for (int i = 0; i < pdata->GetPoints()->GetNumberOfPoints(); ++i)
+ for (long i = 0; i < pdata->GetPoints()->GetNumberOfPoints(); ++i)
{
pcl::PointNormal pt;
double* ptr = pdata->GetPoints()->GetPoint(i);
- pt.x = ptr[0];
- pt.y = ptr[1];
- pt.z = ptr[2];
+ pt.x = static_cast(ptr[0]);
+ pt.y = static_cast(ptr[1]);
+ pt.z = static_cast(ptr[2]);
double* norm = pdata->GetPointData()->GetNormals()->GetTuple(i);
- pt.normal_x = norm[0];
- pt.normal_y = norm[1];
- pt.normal_z = norm[2];
+ pt.normal_x = static_cast(norm[0]);
+ pt.normal_y = static_cast(norm[1]);
+ pt.normal_z = static_cast(norm[2]);
cloud.push_back(pt);
}
@@ -397,8 +384,8 @@ vtkSmartPointer estimateCurvature(vtkSmartPointer mesh
bool embedRightHandRuleNormals(vtkSmartPointer& data)
{
bool success = true;
- LOG4CXX_DEBUG(VTK_LOGGER, "Embedding mesh normals from right hand rule");
- int size = data->GetNumberOfCells();
+ CONSOLE_BRIDGE_logDebug("Embedding mesh normals from right hand rule");
+ int size = static_cast(data->GetNumberOfCells());
vtkDoubleArray* cell_normals = vtkDoubleArray::New();
cell_normals->SetNumberOfComponents(3);
@@ -475,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);
@@ -487,8 +474,8 @@ 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");
- int size = data->GetNumberOfCells();
+ CONSOLE_BRIDGE_logDebug("Generating Mesh Normals manually");
+ int size = static_cast(data->GetNumberOfCells());
vtkDoubleArray* cell_normals = vtkDoubleArray::New();
cell_normals->SetNumberOfComponents(3);
@@ -530,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();
@@ -545,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/src/vtk_viewer.cpp b/vtk_viewer/src/vtk_viewer.cpp
index 3dad2f8d..86a6b642 100644
--- a/vtk_viewer/src/vtk_viewer.cpp
+++ b/vtk_viewer/src/vtk_viewer.cpp
@@ -3,7 +3,6 @@
* All rights reserved.
*
*/
-
#include "vtk_viewer/vtk_viewer.h"
#include
#include
@@ -55,7 +54,7 @@ namespace vtk_viewer
this->iren_->Start();
}
- void VTKViewer::addPointDataDisplay(vtkPoints* points, std::vector color)
+ void VTKViewer::addPointDataDisplay(vtkPoints* points, const std::vector& color)
{
// Add the grid points to a polydata object
vtkSmartPointer polydata = vtkSmartPointer::New();
@@ -73,7 +72,7 @@ namespace vtk_viewer
vtkSmartPointer points_actor = vtkSmartPointer::New();
points_actor->SetMapper(poly_mappers_.back());
points_actor->GetProperty()->SetPointSize(20);
- points_actor->GetProperty()->SetColor(color[0],color[1],color[2]);
+ points_actor->GetProperty()->SetColor(static_cast(color[0]), static_cast(color[1]), static_cast(color[2]));
this->actors_.push_back(points_actor);
@@ -82,7 +81,7 @@ namespace vtk_viewer
}
- void VTKViewer::addPolyDataDisplay(vtkPolyData* polydata , std::vector color)
+ void VTKViewer::addPolyDataDisplay(vtkPolyData* polydata, const std::vector& color)
{
// create mapper and add to list
vtkSmartPointer triangulated_mapper = vtkSmartPointer::New();
@@ -92,7 +91,7 @@ namespace vtk_viewer
// create actor and add to list
vtkSmartPointer triangulated_actor = vtkSmartPointer::New();
triangulated_actor->SetMapper(poly_mappers_.back());
- triangulated_actor->GetProperty()->SetColor(color[0],color[1],color[2]);
+ triangulated_actor->GetProperty()->SetColor(static_cast(color[0]), static_cast(color[1]), static_cast(color[2]));
this->actors_.push_back(triangulated_actor);
@@ -145,7 +144,7 @@ namespace vtk_viewer
glyph->Update();
}
- void VTKViewer::addPolyNormalsDisplay(vtkPolyData* polydata, std::vector color, double scale)
+ void VTKViewer::addPolyNormalsDisplay(vtkPolyData* polydata, const std::vector& color, double scale)
{
VTK_SP(vtkGlyph3D, glyph);
makeGlyphs(polydata, false, glyph, scale);
@@ -159,7 +158,7 @@ namespace vtk_viewer
// create actor and add to list
vtkSmartPointer triangulated_actor = vtkSmartPointer::New();
triangulated_actor->SetMapper(poly_mappers_.back());
- triangulated_actor->GetProperty()->SetColor(color[0],color[1],color[2]);
+ triangulated_actor->GetProperty()->SetColor(static_cast(color[0]), static_cast(color[1]), static_cast(color[2]));
this->actors_.push_back(triangulated_actor);
@@ -167,7 +166,7 @@ namespace vtk_viewer
this->renderer_->AddActor(actors_.back());
}
- void VTKViewer::addCellNormalDisplay(vtkPolyData *polydata, std::vector color, double scale)
+ void VTKViewer::addCellNormalDisplay(vtkPolyData *polydata, const std::vector& color, double scale)
{
// get cell and point data
@@ -203,7 +202,7 @@ namespace vtk_viewer
addPolyNormalsDisplay(centroid_polydata, color, scale);
}
- bool VTKViewer::removeObjectDisplay(int index)
+ bool VTKViewer::removeObjectDisplay(std::size_t index)
{
if(index >= actors_.size())
{
@@ -214,8 +213,9 @@ namespace vtk_viewer
renderer_->RemoveActor(actors_[index]);
// Delete the actor then the mapper associated with the data
- actors_.erase(actors_.begin() + index);
- poly_mappers_.erase(poly_mappers_.begin() + index);
+ actors_.erase(actors_.begin() + static_cast(index));
+ poly_mappers_.erase(poly_mappers_.begin() + static_cast(index));
+ return true;
}
void VTKViewer::removeAllDisplays()
diff --git a/vtk_viewer/test/CMakeLists.txt b/vtk_viewer/test/CMakeLists.txt
new file mode 100644
index 00000000..2c569f8c
--- /dev/null
+++ b/vtk_viewer/test/CMakeLists.txt
@@ -0,0 +1,12 @@
+find_package(GTest REQUIRED)
+
+add_executable(${PROJECT_NAME}_unit utest.cpp)
+target_link_libraries(${PROJECT_NAME}_unit PRIVATE GTest::GTest GTest::Main ${PROJECT_NAME} ${PCL_LIBRARIES} ${VTK_LIBRARIES})
+target_clang_tidy(${PROJECT_NAME}_unit)
+target_cxx_version(${PROJECT_NAME} PRIVATE VERSION 14)
+target_include_what_you_use(${PROJECT_NAME})
+target_cppcheck(${PROJECT_NAME})
+add_code_coverage(${PROJECT_NAME}_unit ALL EXCLUDE ${COVERAGE_EXCLUDE})
+add_gtest_discover_tests(${PROJECT_NAME}_unit)
+add_dependencies(${PROJECT_NAME}_unit ${PROJECT_NAME})
+add_dependencies(run_tests ${PROJECT_NAME}_unit)
diff --git a/vtk_viewer/test/utest.cpp b/vtk_viewer/test/utest.cpp
index 55e709c1..8c8d4fe4 100644
--- a/vtk_viewer/test/utest.cpp
+++ b/vtk_viewer/test/utest.cpp
@@ -39,27 +39,25 @@ TEST(ViewerTest, TestCase1)
cout << "cutter points: " << cut->GetPoints()->GetNumberOfPoints() << "\n";
cout << "cutter lines: " << cut->GetNumberOfLines() << "\n";
-
-
vtk_viewer::VTKViewer viz;
std::vector color(3);
// Display mesh results
- color[0] = 0.2;
- color[1] = 0.9;
- color[2] = 0.9;
+ color[0] = 0.2f;
+ color[1] = 0.9f;
+ color[2] = 0.9f;
viz.addPointDataDisplay(points, color);
// Display mesh results
- color[0] = 0.2;
- color[1] = 0.2;
- color[2] = 0.9;
+ color[0] = 0.2f;
+ color[1] = 0.2f;
+ color[2] = 0.9f;
//viz.addPolyDataDisplay(data, color);
- color[0] = 0.1;
- color[1] = 0.9;
- color[2] = 0.1;
+ color[0] = 0.1f;
+ color[1] = 0.9f;
+ color[2] = 0.1f;
//viz.addCellNormalDisplay(data, color, 1.0);
viz.addPolyDataDisplay(cut,color);
@@ -67,7 +65,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();