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

[ROS-O] patches #2853

Open
wants to merge 2 commits into
base: master
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
2 changes: 1 addition & 1 deletion jsk_pcl_ros_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ jsk_pcl_util_nodelet(src/marker_array_voxel_to_pointcloud_nodelet.cpp
add_library(jsk_pcl_ros_utils SHARED ${jsk_pcl_util_nodelet_sources})
add_dependencies(jsk_pcl_ros_utils ${PROJECT_NAME}_gencfg)
target_link_libraries(jsk_pcl_ros_utils
${catkin_LIBRARIES} ${pcl_ros_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp)
${catkin_LIBRARIES} ${pcl_ros_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp)

get_property(dirs DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY INCLUDE_DIRECTORIES)

Expand Down
5 changes: 5 additions & 0 deletions jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,11 @@ namespace jsk_pcl_ros_utils
sub_.shutdown();
}

// pcl removed the method by 1.13, no harm in defining it ourselves to use below
#if __cplusplus >= 201103L
#define pcl_isfinite(x) std::isfinite(x)
#endif

void NormalFlipToFrame::flip(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
{
vital_checker_->poke();
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace jsk_pcl_ros_utils

void PointCloudToPCD::savePCD()
{
pcl::PCLPointCloud2::ConstPtr cloud;
boost::shared_ptr<const pcl::PCLPointCloud2> cloud;
cloud = ros::topic::waitForMessage<pcl::PCLPointCloud2>("input", *pnh_);
if ((cloud->width * cloud->height) == 0)
{
Expand Down
3 changes: 0 additions & 3 deletions jsk_recognition_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,6 @@ cmake_minimum_required(VERSION 2.8.3)
project(jsk_recognition_msgs)
find_package(catkin REQUIRED
std_msgs sensor_msgs geometry_msgs message_generation pcl_msgs jsk_footstep_msgs)
if(NOT $ENV{ROS_DISTRO} STREQUAL "indigo") # on noetic it needs catkin_install_python to support Python3 and it does not work on indigo for some reason...
catkin_python_setup()
endif()
add_message_files(
FILES
Accuracy.msg
Expand Down
17 changes: 0 additions & 17 deletions jsk_recognition_msgs/setup.py

This file was deleted.

Loading