diff --git a/sensor_msgs/CMakeLists.txt b/sensor_msgs/CMakeLists.txt index 56592fa3..06076c48 100644 --- a/sensor_msgs/CMakeLists.txt +++ b/sensor_msgs/CMakeLists.txt @@ -2,8 +2,6 @@ cmake_minimum_required(VERSION 2.8.3) project(sensor_msgs) find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) -# We want boost/format.hpp, which isn't in its own component. -find_package(Boost REQUIRED) # For point_cloud2.py catkin_python_setup() @@ -49,8 +47,7 @@ generate_messages(DEPENDENCIES geometry_msgs std_msgs) catkin_package( INCLUDE_DIRS include - CATKIN_DEPENDS geometry_msgs message_runtime std_msgs - DEPENDS Boost) + CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} diff --git a/sensor_msgs/include/sensor_msgs/point_cloud_conversion.h b/sensor_msgs/include/sensor_msgs/point_cloud_conversion.h index 698d6c33..f63ed2f1 100644 --- a/sensor_msgs/include/sensor_msgs/point_cloud_conversion.h +++ b/sensor_msgs/include/sensor_msgs/point_cloud_conversion.h @@ -117,7 +117,8 @@ static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud { if (input.fields[d].datatype != sensor_msgs::PointField::FLOAT32) { - std::cerr << boost::str(boost::format("sensor_msgs::PointCloud accepts only float32 values, but field %d (%s) has field type %d!")%(int)d% input.fields[d].name%input.fields[d].datatype) << std::endl; + std::cerr << "sensor_msgs::PointCloud accepts only float32 values, but field "\ + <<(int)d << "( " << input.fields[d].name <<") has field type " << input.fields[d].datatype << "!" << std::endl; } }