diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..ea1ebc9 --- /dev/null +++ b/.gitignore @@ -0,0 +1,34 @@ +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +# Build Folder +build/* +xcodebuild/* +build2/* +xcodebuild2/* diff --git a/CMakeLists.txt b/CMakeLists.txt index 3eb1047..bc2b8be 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,8 +1,23 @@ -project(ObjRecRANSACRun) -cmake_minimum_required(VERSION 2.8.3) +project(objrecransac) + +cmake_minimum_required(VERSION 2.8.12) + + + +# optional for ROS build https://github.com/catkin/catkin_tools +find_package(catkin) + +if(NOT EXISTS OBJREC_USE_CUDA) + FIND_PACKAGE(CUDA) + if(CUDA_FOUND) + set(OBJREC_USE_CUDA TRUE) + endif() +endif() +cmake_policy(SET CMP0053 OLD) IF(OBJREC_USE_CUDA) set(OBJREC_CUDA_DEVICE_ID 1 CACHE STRING "Which GPU device to use when running") + message(STATUS "CUDA Found and enabled with OBJREC_USE_CUDA=TRUE, Using CUDA GPU Device # " ${OBJREC_CUDA_DEVICE_ID}) add_definitions(-DUSE_CUDA) add_definitions(-DCUDA_DEVICE_ID=${OBJREC_CUDA_DEVICE_ID}) @@ -14,13 +29,25 @@ IF(OBJREC_USE_CUDA) #add_definitions(-DOBJ_REC_RANSAC_VERBOSE) #add_definitions(-DOBJ_REC_RANSAC_VERBOSE_1) #add_definitions(-DOBJ_REC_RANSAC_VERBOSE_2) -ENDIF(OBJREC_USE_CUDA) +ENDIF() + +if(CATKIN_FOUND) + option(BUILD_ROS_BINDING "Build ROS Bindings using catkin" ON) + catkin_package( + DEPENDS # none + CATKIN_DEPENDS # none + INCLUDE_DIRS src include + LIBRARIES ObjRecRANSAC + ) +else() + option(BUILD_ROS_BINDING "Build ROS Bindings using catkin" OFF) +endif() find_package(Boost COMPONENTS thread system REQUIRED) include_directories(${Boost_INCLUDE_DIRS}) find_package(PCL REQUIRED) -find_package(OpenMP REQUIRED) +find_package(OpenMP) find_package(VTK) IF(NOT VTK_FOUND) @@ -47,6 +74,7 @@ endif() IF(OPENMP_FOUND) set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") + add_definitions(-DUSE_OPENMP) message (STATUS "Found OpenMP") ENDIF(OPENMP_FOUND) @@ -77,37 +105,66 @@ else() add_executable(ObjRecRANSACRun main.cpp) endif() -target_link_libraries(ObjRecRANSACRun ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics vtkIO vtkCommon vtkRendering ${OpenCV_LIBS} rt ${PCL_LIBRARIES}) +target_link_libraries(ObjRecRANSACRun ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics ${VTK_LIBRARIES} ${OpenCV_LIBS} ${PCL_LIBRARIES}) #add_library(Utility utility.h utility.cpp) #target_link_libraries(Utility ${PCL_LIBRARIES} ${OpenCV_LIBS}) add_library(Greedy src/Greedy/utility.h src/Greedy/utility.cpp src/Greedy/seg.h src/Greedy/seg.cpp) -target_link_libraries(Greedy ${PCL_LIBRARIES} ${OpenCV_LIBS}) +target_link_libraries(Greedy ObjRecRANSAC ${PCL_LIBRARIES} ${OpenCV_LIBS}) add_executable(SegRansac main_seg.cpp) -target_link_libraries(SegRansac ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics vtkIO vtkCommon vtkRendering Greedy ${OpenCV_LIBS} ${PCL_LIBRARIES} rt) +target_link_libraries(SegRansac ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics ${VTK_LIBRARIES} Greedy ${OpenCV_LIBS} ${PCL_LIBRARIES}) add_executable(poseTest main_test_pose.cpp) -target_link_libraries(poseTest ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics vtkIO vtkCommon vtkRendering Greedy ${OpenCV_LIBS} ${PCL_LIBRARIES} rt) +target_link_libraries(poseTest ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics ${VTK_LIBRARIES} Greedy ${OpenCV_LIBS} ${PCL_LIBRARIES}) add_executable(segTest main_test_seg.cpp) -target_link_libraries(segTest ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics vtkIO vtkCommon vtkRendering Greedy ${OpenCV_LIBS} ${PCL_LIBRARIES} rt) - -install(TARGETS ObjRecRANSACRun - RUNTIME DESTINATION bin - LIBRARY DESTINATION lib - ARCHIVE DESTINATION lib) - -install(DIRECTORY src/ - DESTINATION include - PATTERN "*.cpp" EXCLUDE - PATTERN "*.cu" EXCLUDE - PATTERN "*.c" EXCLUDE - ) +target_link_libraries(segTest ObjRecRANSAC BasicToolsL1 BasicTools VtkBasics ${VTK_LIBRARIES} Greedy ${OpenCV_LIBS} ${PCL_LIBRARIES}) + +if(UNIX AND NOT APPLE) + target_link_libraries(ObjRecRANSACRun rt) + target_link_libraries(Greedy rt) + target_link_libraries(poseTest rt) + target_link_libraries(segTest rt) +endif() + + +if(NOT BUILD_ROS_BINDING) + # STANDARD INSTALLATION + install(TARGETS ObjRecRANSACRun + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib) + + install(DIRECTORY src/ + DESTINATION include + PATTERN "*.cpp" EXCLUDE + PATTERN "*.cu" EXCLUDE + PATTERN "*.c" EXCLUDE + ) + + install(DIRECTORY data + DESTINATION share/ObjRecRANSAC) + + install(FILES package.xml + DESTINATION share/ObjRecRANSAC) + +elseif(BUILD_ROS_BINDING) + # CATKIN INSTALLATION + install(DIRECTORY src/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN "*.cpp" EXCLUDE + PATTERN "*.cu" EXCLUDE + PATTERN "*.c" EXCLUDE + ) + + install(DIRECTORY data + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + + install(FILES package.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +endif() -install(DIRECTORY data - DESTINATION share/ObjRecRANSAC) -install(FILES package.xml - DESTINATION share/ObjRecRANSAC) diff --git a/main.cpp b/main.cpp index 6de0b3b..3335ac4 100644 --- a/main.cpp +++ b/main.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #include using namespace std; @@ -293,7 +294,12 @@ void visualize(list >& detectedShapes, vtkPoint // Transform the model instance using the estimated rigid transform vtkTransformPolyDataFilter *transformer = vtkTransformPolyDataFilter::New(); + +#if VTK_MAJOR_VERSION < 6 transformer->SetInput(shape->getHighResModel()); +#else // VTK 6 + transformer->SetInputData(shape->getHighResModel()); +#endif VtkTransform::mat4x4ToTransformer((const double**)mat4x4, transformer); // Visualize the transformed model diff --git a/main_seg.cpp b/main_seg.cpp index 43168f7..caf7377 100644 --- a/main_seg.cpp +++ b/main_seg.cpp @@ -1,7 +1,7 @@ #include "src/Greedy/seg.h" #include #include -#include +#include //========================================================================================================================= diff --git a/package.xml b/package.xml index f1c079a..d391e8d 100644 --- a/package.xml +++ b/package.xml @@ -1,5 +1,5 @@ - ObjRecRANSAC + objrecransac 1.1.0 RANSAC variant for 3D object recognition in occluded scenes diff --git a/src/BasicTools/Aux/Stopwatch.cpp b/src/BasicTools/Aux/Stopwatch.cpp index d47c571..612db59 100644 --- a/src/BasicTools/Aux/Stopwatch.cpp +++ b/src/BasicTools/Aux/Stopwatch.cpp @@ -7,8 +7,22 @@ #include "Stopwatch.h" +#ifdef __APPLE__ +#include "realtime.hpp" +#endif // __APPLE__ + Stopwatch::Stopwatch(bool print_err_msg) { +#ifdef __APPLE__ +#ifdef HAVE_REALTIME + int msToNS = 1000000, period = 1*msToNS, computation = 0.1*msToNS, constraint = 0.5*msToNS; + bool preemptible = false; + if(set_realtime( period, computation, constraint, preemptible)){ + std::cout << "realtime mode successfully enabled!\n"; + }; +#endif // HAVE_REALTIME +#else // __APPLE__ + // LINUX // Measure test time sched_param mySchedParam; mySchedParam.__sched_priority = sched_get_priority_max(SCHED_FIFO); @@ -19,7 +33,6 @@ Stopwatch::Stopwatch(bool print_err_msg) printf("Stopwatch::Stopwatch(): sched_get_priority_max() failed\n"); mySchedParam.__sched_priority = 99; } - if ( sched_setscheduler(0, SCHED_FIFO, &mySchedParam) == -1 && print_err_msg ) { printf("Stopwatch::Stopwatch(): Changing to real-time priority level %i failed. ", mySchedParam.__sched_priority); @@ -41,7 +54,7 @@ Stopwatch::Stopwatch(bool print_err_msg) break; } } - +#endif fflush(stdout); } diff --git a/src/BasicTools/Aux/Stopwatch.h b/src/BasicTools/Aux/Stopwatch.h index 7db1c23..a330ea3 100644 --- a/src/BasicTools/Aux/Stopwatch.h +++ b/src/BasicTools/Aux/Stopwatch.h @@ -16,13 +16,44 @@ #include #include +#ifdef __APPLE__ +#include +#define ORWL_NANO (+1.0E-9) +#define ORWL_GIGA UINT64_C(1000000000) + +static double orwl_timebase = 0.0; +static uint64_t orwl_timestart = 0; + +inline struct timespec orwl_gettime(void) { + // be more careful in a multithreaded environement + if (!orwl_timestart) { + mach_timebase_info_data_t tb = { 0 }; + mach_timebase_info(&tb); + orwl_timebase = tb.numer; + orwl_timebase /= tb.denom; + orwl_timestart = mach_absolute_time(); + } + struct timespec t; + double diff = (mach_absolute_time() - orwl_timestart) * orwl_timebase; + t.tv_sec = diff * ORWL_NANO; + t.tv_nsec = diff - (t.tv_sec * ORWL_GIGA); + return t; +} +#endif // __APPLE__ + class Stopwatch { public: Stopwatch(bool print_err_msg = true); virtual ~Stopwatch(); - void start(){ clock_gettime(CLOCK_REALTIME, &mStart);} + void start(){ +#ifdef __APPLE__ + mStart = orwl_gettime(); +#else + clock_gettime(CLOCK_REALTIME, &mStart); +#endif + } /** Returns the elapsed time in seconds since the last call of 'this->start()'. */ inline double stop(); @@ -35,7 +66,12 @@ class Stopwatch inline double Stopwatch::stop() { - timespec stop; clock_gettime(CLOCK_REALTIME, &stop); + timespec stop; +#ifdef __APPLE__ + stop = orwl_gettime(); +#else + clock_gettime(CLOCK_REALTIME, &stop); +#endif // Return the difference in seconds return (double)(stop.tv_sec - mStart.tv_sec) + ((double)(stop.tv_nsec - mStart.tv_nsec))/1000000000.0; } diff --git a/src/BasicTools/Aux/realtime.hpp b/src/BasicTools/Aux/realtime.hpp new file mode 100644 index 0000000..00aaa10 --- /dev/null +++ b/src/BasicTools/Aux/realtime.hpp @@ -0,0 +1,88 @@ +#ifndef _GRL_REALTIME_HPP_ +#define _GRL_REALTIME_HPP_ + +#ifdef __APPLE__ +#include +#include +#include +#include +//#include +#include +#include +#include +#include + + +static inline uint64_t +nanos_to_abs(uint64_t ns, uint32_t numer, uint32_t denom) +{ + return (uint64_t)(ns * (((double)denom) / ((double)numer))); +} + + +/** + * THREAD_TIME_CONSTRAINT_POLICY: + * + * This scheduling mode is for threads which have real time + * constraints on their execution. + * + * Parameters: + * + * @param period: This is the nominal amount of time between separate + * processing arrivals, specified in absolute time units. A + * value of 0 indicates that there is no inherent periodicity in + * the computation. (nanoseconds) + * + * @param computation: This is the nominal amount of computation + * time needed during a separate processing arrival, specified + * in absolute time units. (nanoseconds) + * + * @param constraint: This is the maximum amount of real time that + * may elapse from the start of a separate processing arrival + * to the end of computation for logically correct functioning, + * specified in absolute time units. Must be (>= computation). + * Note that latency = (constraint - computation). (nanoseconds) + * + * @param preemptible: This indicates that the computation may be + * interrupted, subject to the constraint specified above + * Should almost always be false unless you really need it. (bool) + * + * @see http://www.opensource.apple.com/source/xnu/xnu-2050.18.24/tools/tests/xnu_quick_test/sched_tests.c + * @see https://developer.apple.com/library/mac/documentation/Darwin/Conceptual/KernelProgramming/scheduler/scheduler.html + */ +inline int set_realtime(int period, int computation, int constraint, bool preemptible = false) { + + struct mach_timebase_info mti; + struct thread_time_constraint_policy ttcpolicy; + kern_return_t kret; + + kret = mach_timebase_info(&mti); + + if (kret != KERN_SUCCESS) { + warnx("Could not get timebase info %d", kret); + return 0; + } + + thread_port_t threadport = pthread_mach_thread_np(pthread_self()); + + ttcpolicy.period = nanos_to_abs(period, mti.numer, mti.denom); + ttcpolicy.computation = nanos_to_abs(computation, mti.numer, mti.denom); // HZ/3300; + ttcpolicy.constraint = nanos_to_abs(constraint, mti.numer, mti.denom); // HZ/2200; + ttcpolicy.preemptible = preemptible; + + if ((kret=thread_policy_set(threadport, + THREAD_TIME_CONSTRAINT_POLICY, (thread_policy_t)&ttcpolicy, + THREAD_TIME_CONSTRAINT_POLICY_COUNT)) != KERN_SUCCESS) { + fprintf(stderr, "set_realtime() failed.\n"); + warnx("Failed to set_realtime %d", kret); + + return 0; + } + return 1; +} +#endif // __APPLE__ + + + + +#endif \ No newline at end of file diff --git a/src/BasicTools/CMakeLists.txt b/src/BasicTools/CMakeLists.txt index 9c4aab0..463082c 100644 --- a/src/BasicTools/CMakeLists.txt +++ b/src/BasicTools/CMakeLists.txt @@ -1,5 +1,6 @@ project(BasicTools) cmake_minimum_required(VERSION 2.6) +cmake_policy(SET CMP0053 OLD) find_package(VTK) @@ -43,7 +44,7 @@ add_library(BasicTools SHARED @_STOCH_@ @_MYVTK_@ ) -target_link_libraries(BasicTools vtkRendering) +target_link_libraries(BasicTools ${VTK_LIBRARIES}) add_library(BasicToolsStatic STATIC @_AUX_@ diff --git a/src/BasicTools/Vtk/VtkMeshSampler.cpp b/src/BasicTools/Vtk/VtkMeshSampler.cpp index 96e5e9b..68f8572 100644 --- a/src/BasicTools/Vtk/VtkMeshSampler.cpp +++ b/src/BasicTools/Vtk/VtkMeshSampler.cpp @@ -8,6 +8,7 @@ #include #include #include +#include #include using namespace std; @@ -63,7 +64,11 @@ void VtkMeshSampler::sample(vtkPolyData* in, vtkPoints* out, int numberOfPoints) vtkTriangleFilter* tria_filter = vtkTriangleFilter::New(); tria_filter->PassLinesOff(); tria_filter->PassVertsOff(); - tria_filter->SetInput(in); +#if VTK_MAJOR_VERSION < 6 + tria_filter->SetInput (in); +#else // VTK 6 + tria_filter->SetInputData (in); +#endif tria_filter->Update(); vtkPolyData* mesh = tria_filter->GetOutput(); mesh->BuildLinks(); @@ -133,7 +138,11 @@ void VtkMeshSampler::estimateAndSample(vtkPolyData* in, vtkPolyData* out, int nu vtkTriangleFilter* tria_filter = vtkTriangleFilter::New(); tria_filter->PassLinesOff(); tria_filter->PassVertsOff(); - tria_filter->SetInput(in); +#if VTK_MAJOR_VERSION < 6 + tria_filter->SetInput (in); +#else // VTK 6 + tria_filter->SetInputData (in); +#endif tria_filter->Update(); vtkPolyDataNormals* normals_filter = vtkPolyDataNormals::New(); diff --git a/src/BasicToolsL1/CMakeLists.txt b/src/BasicToolsL1/CMakeLists.txt index a8d150c..ec59804 100644 --- a/src/BasicToolsL1/CMakeLists.txt +++ b/src/BasicToolsL1/CMakeLists.txt @@ -1,5 +1,6 @@ project(BasicToolsL1) cmake_minimum_required(VERSION 2.6) +cmake_policy(SET CMP0053 OLD) FILE(GLOB _BTL1_CUR_ *.cpp) FILE(GLOB _BTL1_EIG3x3_ eigen3x3/*.cpp) diff --git a/src/Greedy/seg.cpp b/src/Greedy/seg.cpp index cbebe68..cf2fc09 100644 --- a/src/Greedy/seg.cpp +++ b/src/Greedy/seg.cpp @@ -1,4 +1,4 @@ -#include +#include #include #include "seg.h" diff --git a/src/Greedy/utility.h b/src/Greedy/utility.h index 3bc0230..f412f70 100644 --- a/src/Greedy/utility.h +++ b/src/Greedy/utility.h @@ -57,7 +57,9 @@ #include #include +#ifdef USE_OPENMP #include +#endif // USE_OPENMP typedef pcl::PointXYZ myPointXYZ; typedef pcl::PointXYZRGBA PointT; diff --git a/src/ObjRecRANSAC/CMakeLists.txt b/src/ObjRecRANSAC/CMakeLists.txt index 640c86d..fa3e89f 100755 --- a/src/ObjRecRANSAC/CMakeLists.txt +++ b/src/ObjRecRANSAC/CMakeLists.txt @@ -1,6 +1,6 @@ project(ObjRecRANSAC) cmake_minimum_required(VERSION 2.6) - +cmake_policy(SET CMP0053 OLD) find_package(VTK) IF(NOT VTK_FOUND) @@ -114,6 +114,13 @@ else() @_ORR_SH_@ ) set_target_properties(ObjRecRANSACStatic PROPERTIES OUTPUT_NAME ObjRecRANSAC) + + + find_package(PythonLibs) + if(PYTHONLIBS_FOUND) + target_link_libraries(ObjRecRANSAC ${PYTHON_LIBRARIES}) + target_link_libraries(ObjRecRANSACStatic ${PYTHON_LIBRARIES}) + endif() endif() install(TARGETS ObjRecRANSAC ObjRecRANSACStatic diff --git a/src/VtkBasics/CMakeLists.txt b/src/VtkBasics/CMakeLists.txt index 1c5d301..06217cb 100644 --- a/src/VtkBasics/CMakeLists.txt +++ b/src/VtkBasics/CMakeLists.txt @@ -1,6 +1,6 @@ project(VtkBasics) cmake_minimum_required(VERSION 2.6) - +cmake_policy(SET CMP0053 OLD) find_package(VTK) IF(NOT VTK_FOUND) @@ -25,6 +25,16 @@ add_library(VtkBasics SHARED add_library(VtkBasicsStatic STATIC @_VTK_@ ) + +target_link_libraries(VtkBasics ${VTK_LIBRARIES}) +target_link_libraries(VtkBasicsStatic ${VTK_LIBRARIES}) + +find_package(PythonLibs) +if(PYTHONLIBS_FOUND) + target_link_libraries(VtkBasics ${PYTHON_LIBRARIES}) + target_link_libraries(VtkBasicsStatic ${PYTHON_LIBRARIES}) +endif() + set_target_properties(VtkBasicsStatic PROPERTIES OUTPUT_NAME VtkBasics) install(TARGETS VtkBasics VtkBasicsStatic diff --git a/src/VtkBasics/VtkLine.cpp b/src/VtkBasics/VtkLine.cpp index c366650..67d76dc 100644 --- a/src/VtkBasics/VtkLine.cpp +++ b/src/VtkBasics/VtkLine.cpp @@ -1,4 +1,5 @@ #include "VtkLine.h" +#include VtkLine::VtkLine() { @@ -24,10 +25,16 @@ void VtkLine::init(double x1, double y1, double z1, double x2, double y2, double mLine->SetPoint1(x1, y1, z1); mLine->SetPoint2(x2, y2, z2); + +#if VTK_MAJOR_VERSION < 6 mTube->SetInput(mLine->GetOutput()); + mMapper->SetInput(mTube->GetOutput()); +#else // VTK 6 + mTube->SetInputData(mLine->GetOutput()); + mMapper->SetInputData(mTube->GetOutput()); +#endif mTube->SetNumberOfSides(8); mTube->SetRadius(radius); - mMapper->SetInput(mTube->GetOutput()); mActor->SetMapper(mMapper); mActor->GetProperty()->SetColor(1.0, 0.0, 0.0); mActor->SetPosition(0.0, 0.0, 0.0); diff --git a/src/VtkBasics/VtkPoints.cpp b/src/VtkBasics/VtkPoints.cpp index df90742..84526c7 100644 --- a/src/VtkBasics/VtkPoints.cpp +++ b/src/VtkBasics/VtkPoints.cpp @@ -1,6 +1,7 @@ #include "VtkPoints.h" #include #include +#include VtkPoints::VtkPoints(vtkIdList* ids, vtkPoints* input) { @@ -113,7 +114,12 @@ VtkPoints::VtkPoints(vtkPolyData* input, bool colorModeByScalar) mGlyphs->SetScaleFactor(1.0); mGlyphs->SetSourceConnection(mSphereSrc->GetOutputPort()); - mGlyphs->SetInput(mPoints); + +#if VTK_MAJOR_VERSION < 6 + mGlyphs->SetInput(input); +#else // VTK 6 + mGlyphs->SetInputData(mPoints); +#endif if ( colorModeByScalar ) { @@ -159,7 +165,12 @@ void VtkPoints::init(vtkPoints *input) mGlyphs->ScalingOn(); mGlyphs->SetScaleFactor(1.0); mGlyphs->SetSourceConnection(mSphereSrc->GetOutputPort()); + +#if VTK_MAJOR_VERSION < 6 mGlyphs->SetInput(mPoints); +#else // VTK 6 + mGlyphs->SetInputData(mPoints); +#endif mMapper->ScalarVisibilityOff(); mMapper->SetInputConnection(mGlyphs->GetOutputPort()); diff --git a/src/VtkBasics/VtkPoints.h b/src/VtkBasics/VtkPoints.h index 08f5330..42b74a2 100644 --- a/src/VtkBasics/VtkPoints.h +++ b/src/VtkBasics/VtkPoints.h @@ -10,6 +10,7 @@ #include #include #include +#include #include using namespace std; @@ -33,7 +34,11 @@ class VtkPoints: public VtkObject /** Inherited from 'VtkObject' */ vtkPolyData* getPolyData(){ return mPoints;} +#if VTK_MAJOR_VERSION < 6 void updateGlyphsGeometry(){ mPoints->Update(); mGlyphs->Update(); mSphereSrc->Update();} +#else // VTK 6 + void updateGlyphsGeometry(){ mMapper->Update(); mGlyphs->Update(); mSphereSrc->Update();} +#endif double getNextPointMeanDistance(); void setColor(double r, double g, double b){ mActor->GetProperty()->SetColor(r, g, b);} diff --git a/src/VtkBasics/VtkPolyData.cpp b/src/VtkBasics/VtkPolyData.cpp index c2b078c..c225b04 100644 --- a/src/VtkBasics/VtkPolyData.cpp +++ b/src/VtkBasics/VtkPolyData.cpp @@ -3,6 +3,7 @@ #include #include #include +#include VtkPolyData::VtkPolyData(vtkPolyData *polyData) @@ -19,7 +20,12 @@ VtkPolyData::VtkPolyData(vtkPolyData *polyData) } mMapper = vtkPolyDataMapper::New(); + +#if VTK_MAJOR_VERSION < 6 mMapper->SetInput(mPolyData); +#else // VTK 6 + mMapper->SetInputData(mPolyData); +#endif mActor = vtkActor::New(); mActor->SetMapper(mMapper);