Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

OSX, VTK6, OpenMP #6

Open
wants to merge 11 commits into
base: master
Choose a base branch
from
34 changes: 34 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -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/*
107 changes: 82 additions & 25 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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})

Expand All @@ -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)
Expand All @@ -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)

Expand Down Expand Up @@ -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)
6 changes: 6 additions & 0 deletions main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <vtkPolyData.h>
#include <vtkPolyDataReader.h>
#include <vtkTransformPolyDataFilter.h>
#include <vtkVersion.h>
#include <list>

using namespace std;
Expand Down Expand Up @@ -293,7 +294,12 @@ void visualize(list<boost::shared_ptr<PointSetShape> >& 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
Expand Down
2 changes: 1 addition & 1 deletion main_seg.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "src/Greedy/seg.h"
#include <sys/time.h>
#include <eigen3/Eigen/src/Geometry/Quaternion.h>
#include <bits/algorithmfwd.h>
#include <algorithm>

//=========================================================================================================================

Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<package>
<name>ObjRecRANSAC</name>
<name>objrecransac</name>
<version>1.1.0</version>
<description>
RANSAC variant for 3D object recognition in occluded scenes
Expand Down
17 changes: 15 additions & 2 deletions src/BasicTools/Aux/Stopwatch.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand All @@ -41,7 +54,7 @@ Stopwatch::Stopwatch(bool print_err_msg)
break;
}
}

#endif
fflush(stdout);
}

Expand Down
40 changes: 38 additions & 2 deletions src/BasicTools/Aux/Stopwatch.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,44 @@
#include <errno.h>
#include <sched.h>

#ifdef __APPLE__
#include <mach/mach_time.h>
#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();
Expand All @@ -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;
}
Expand Down
Loading