Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
53 changes: 34 additions & 19 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,23 +1,19 @@
cmake_minimum_required(VERSION 2.8)
cmake_minimum_required(VERSION 3.16)
project(nimbro_primitive_fitter)

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${PROJECT_SOURCE_DIR}/cmake) # For finding custom .cmake files

find_package(catkin REQUIRED COMPONENTS
cmake_modules
roslib
roscpp
rospack
rosparam
)
SET(CMAKE_VERBOSE_MAKEFILE TRUE)
SET(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17")
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${PROJECT_SOURCE_DIR}/cmake) # For finding custom .cmake files
set(DISABLE_PAL_FLAGS true)

find_package(Boost REQUIRED COMPONENTS system regex)
find_package(Eigen3 REQUIRED)
find_package(PugiXML REQUIRED)
find_package(PkgConfig REQUIRED)

pkg_check_modules(roboptim-capsule REQUIRED roboptim-capsule)
find_package(roboptim-capsule REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)

include_directories(
include
Expand All @@ -30,20 +26,20 @@ include_directories(
contrib/approx_mvbb/external/GeometryPredicates/include/ApproxMVBB/GeometryPredicates
${catkin_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${PUGIXML_INCLUDE_DIR}
${PUGIXML_INCLUDE_DIR}
${roboptim-capsule_INCLUDE_DIRS}
)

link_directories(
${roboptim-capsule_LIBRARY_DIRS}
)

catkin_package(
#catkin_package(
# INCLUDE_DIRS include
# LIBRARIES nimbro_primitive_fitter
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
#)

add_library(approx_mvbb
contrib/approx_mvbb/src/ApproxMVBB/AABB.cpp
Expand All @@ -60,17 +56,36 @@ add_library(approx_mvbb
contrib/approx_mvbb/external/Diameter/src/EstimateDiameter.cpp
)

add_executable(nimbro_primitive_fitter
add_executable(nimbro_primitive_fitter
src/primitive_fitter.cpp
src/inertia.cpp
src/util.cpp
src/main.cpp
)

target_link_libraries(nimbro_primitive_fitter
${catkin_LIBRARIES}
rclcpp::rclcpp
${PUGIXML_LIBRARIES}
${roboptim-capsule_LIBRARIES}
roboptim-capsule::roboptim-capsule
approx_mvbb
)


string(REPLACE ";" " " WARNING_CXX_FLAGS "${WARNING_CXX_FLAGS_LIST}")

set(CMAKE_CXX_FLAGS "${WARNING_CXX_FLAGS} ${CMAKE_CXX_FLAGS}")
install(TARGETS
nimbro_primitive_fitter
DESTINATION lib/${PROJECT_NAME}
)

install(TARGETS
approx_mvbb
DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY launch models
DESTINATION share/${PROJECT_NAME}
)

ament_package()
9 changes: 1 addition & 8 deletions include/nimbro_primitive_fitter/inertia.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,5 @@ class MyEdge : public vcg::Edge<MyUsedTypes> {};
class MyMesh : public vcg::tri::TriMesh< std::vector<MyVertex>, std::vector<MyFace> , std::vector<MyEdge> > {};


std::string getFileExtension(std::string meshfile);
//std::string getFileExtension(std::string meshfile, const rclcpp::Node &nh);

/*
* Reads URDF and updates inertia values and center of mass for each link.
* 'urdf_filename': Path of the URDF
* 'visual': If true, visual meshes are used for calculation.
* If false, collision meshes are used.
*/
void update_inertia(std::string in_filename, std::string out_filename, bool visual, const ros::NodeHandle nh);
Loading