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

PCL "filters" module not included #41

Open
wants to merge 2 commits into
base: jade-devel
Choose a base branch
from
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
14 changes: 7 additions & 7 deletions dvo_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(dvo_core)

find_package(catkin REQUIRED)
find_package(cmake_modules REQUIRED)
find_package(PCL REQUIRED COMPONENTS common)
find_package(PCL REQUIRED COMPONENTS common filters)
find_package(Eigen3 REQUIRED)
find_package(sophus REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)
Expand All @@ -28,7 +28,7 @@ include_directories(
${PCL_INCLUDE_DIRS}
)

add_library(dvo_core
add_library(dvo_core
src/core/interpolation.cpp
src/core/intrinsic_matrix.cpp
src/core/least_squares.cpp
Expand All @@ -38,19 +38,19 @@ add_library(dvo_core
src/core/point_selection.cpp
src/core/surface_pyramid.cpp
src/core/weight_calculation.cpp

src/util/histogram.cpp

src/visualization/camera_trajectory_visualizer.cpp

src/dense_tracking.cpp
src/dense_tracking_impl.cpp
src/dense_tracking_config.cpp
)

target_link_libraries(dvo_core
target_link_libraries(dvo_core
tbb
boost_thread
boost_thread
${PCL_LIBRARIES}
)

Expand Down
6 changes: 3 additions & 3 deletions dvo_ros/src/camera_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ CameraBase::CameraBase(ros::NodeHandle& nh, ros::NodeHandle& nh_private) :
nh_(nh),
nh_private_(nh_private),

rgb_image_subscriber_(nh, "camera/rgb/image_rect", 1),
depth_image_subscriber_(nh, "camera/depth_registered/image_rect_raw", 1),
rgb_image_subscriber_(nh, "/camera/rgb/image_rect_color", 1),
depth_image_subscriber_(nh, "/camera/depth_registered/sw_registered/image_rect_raw", 1),
rgb_camera_info_subscriber_(nh, "camera/rgb/camera_info", 1),
depth_camera_info_subscriber_(nh, "camera/depth_registered/camera_info", 1),
depth_camera_info_subscriber_(nh, "camera/depth/camera_info", 1),

synchronizer_(RGBDWithCameraInfoPolicy(5), rgb_image_subscriber_, depth_image_subscriber_, rgb_camera_info_subscriber_, depth_camera_info_subscriber_),

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -412,7 +412,7 @@ struct RosCameraTrajectoryVisualizerImpl
{
image_topic_ = it_.advertise("image", 1, true);
point_cloud_topic_ = nh_.advertise<AsyncPointCloudBuilder::PointCloud>("cloud", 1, true);
update_timer_ = nh_.createTimer(ros::Duration(1.0), &RosCameraTrajectoryVisualizerImpl::update, this, false, true);
update_timer_ = nh_.createTimer(ros::Duration(0.1), &RosCameraTrajectoryVisualizerImpl::update, this, false, true);
}

~RosCameraTrajectoryVisualizerImpl()
Expand Down