-
Notifications
You must be signed in to change notification settings - Fork 227
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Image Transport rework port in progress for review (#84)
* Remove boost where possible. * ros::VoidPtr to std::shared_ptr<void> * Conversions around boost where necessary. * Ignore other packages for now. * Basic ament_cmake port. * Port camera_common. * Port publisher. * Convert subscriber. * Port single_subscriber_publisher. * Type updates. VoidPtr -> std::shared_ptr<void> sensor_msgs::Image -> sensor_msgs::msg::Image sensor_msgs::ImageConstPtr -> sensor_msgs::msg::Image::ConstSharedPtr * Replace queue_size and latch with qos. * Implement simple subscriber and publisher. * Refactor. * Restore comments and naming. * Fixup transport and add republisher back in. * Add library export. * Address reviewer feedback. * Clean up a few warnings, remove boost headers. * compile_definitions -> compile_options * Reviewer feedback on necessary includes. * Address comments about CMakeLists and package. * Switch to RCLCPP loggers. * ERROR -> FATAL where asserts were used. * Add TODOs for ROS2 assert equivalents back. * Added a TODO for getNumPublishers.
- Loading branch information
Showing
40 changed files
with
1,461 additions
and
1,090 deletions.
There are no files selected for viewing
Empty file.
Empty file.
Empty file.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,69 +1,121 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
cmake_minimum_required(VERSION 3.5) | ||
|
||
project(image_transport) | ||
|
||
find_package(catkin REQUIRED | ||
COMPONENTS | ||
message_filters | ||
pluginlib | ||
rosconsole | ||
roscpp | ||
roslib | ||
sensor_msgs | ||
) | ||
# Default to C++14 | ||
if(NOT CMAKE_CXX_STANDARD) | ||
set(CMAKE_CXX_STANDARD 14) | ||
endif() | ||
|
||
find_package(Boost REQUIRED) | ||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
add_compile_options(-Wall -Wextra -Wpedantic) | ||
endif() | ||
|
||
catkin_package( | ||
INCLUDE_DIRS include | ||
LIBRARIES ${PROJECT_NAME} | ||
DEPENDS message_filters pluginlib rosconsole roscpp roslib sensor_msgs | ||
) | ||
find_package(ament_cmake_ros REQUIRED) | ||
|
||
find_package(message_filters REQUIRED) | ||
find_package(pluginlib REQUIRED) | ||
find_package(rclcpp REQUIRED) | ||
find_package(sensor_msgs REQUIRED) | ||
|
||
include_directories(include ${catkin_INCLUDE_DIRS}) | ||
include_directories(include) | ||
|
||
# Build libimage_transport | ||
# Build image_transport library | ||
add_library(${PROJECT_NAME} | ||
src/camera_common.cpp | ||
src/publisher.cpp | ||
src/subscriber.cpp | ||
src/single_subscriber_publisher.cpp | ||
src/camera_publisher.cpp | ||
src/camera_subscriber.cpp | ||
src/image_transport.cpp | ||
src/publisher.cpp | ||
src/single_subscriber_publisher.cpp | ||
src/subscriber.cpp | ||
) | ||
add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) | ||
target_link_libraries(${PROJECT_NAME} | ||
${Boost_LIBRARIES} | ||
${catkin_LIBRARIES} | ||
|
||
ament_target_dependencies(${PROJECT_NAME} | ||
"message_filters" | ||
"pluginlib" | ||
"rclcpp" | ||
"sensor_msgs" | ||
) | ||
|
||
# Build libimage_transport_plugins | ||
add_library(${PROJECT_NAME}_plugins src/manifest.cpp src/raw_publisher.cpp) | ||
target_link_libraries(${PROJECT_NAME}_plugins ${PROJECT_NAME}) | ||
target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") | ||
|
||
install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_plugins | ||
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
COMPONENT main | ||
) | ||
install(DIRECTORY include/${PROJECT_NAME}/ | ||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} | ||
# Build image_transport_plugins library (raw) | ||
add_library(${PROJECT_NAME}_plugins | ||
src/manifest.cpp | ||
) | ||
target_link_libraries(${PROJECT_NAME}_plugins ${PROJECT_NAME}) | ||
|
||
# add two execs | ||
# Build list_trasnports | ||
add_executable(list_transports src/list_transports.cpp) | ||
target_link_libraries(list_transports ${PROJECT_NAME}) | ||
|
||
# Build republish | ||
add_executable(republish src/republish.cpp) | ||
target_link_libraries(republish ${PROJECT_NAME}) | ||
|
||
add_executable(list_transports src/list_transports.cpp) | ||
target_link_libraries(list_transports | ||
${PROJECT_NAME} | ||
${catkin_LIBRARIES} | ||
# Install plugin descriptions | ||
pluginlib_export_plugin_description_file(image_transport default_plugins.xml) | ||
|
||
# Install libraries | ||
install( | ||
TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_plugins | ||
ARCHIVE DESTINATION lib | ||
LIBRARY DESTINATION lib | ||
RUNTIME DESTINATION bin | ||
) | ||
|
||
install(TARGETS list_transports republish | ||
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | ||
# Install executables | ||
install( | ||
TARGETS list_transports republish | ||
RUNTIME DESTINATION lib/${PROJECT_NAME} | ||
) | ||
|
||
# add xml file | ||
install(FILES default_plugins.xml | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | ||
# Install include directories | ||
install( | ||
DIRECTORY include/ | ||
DESTINATION include | ||
) | ||
|
||
ament_export_include_directories(include) | ||
ament_export_libraries(${PROJECT_NAME}) | ||
|
||
ament_export_dependencies(message_filters) | ||
ament_export_dependencies(rclcpp) | ||
ament_export_dependencies(sensor_msgs) | ||
ament_export_dependencies(pluginlib) | ||
|
||
if(BUILD_TESTING) | ||
#TODO(ros2) enable linting | ||
#find_package(ament_lint_auto REQUIRED) | ||
#ament_lint_auto_find_test_dependencies() | ||
|
||
find_package(ament_cmake_gtest) | ||
|
||
ament_add_gtest(${PROJECT_NAME}-camera_common test/test_camera_common.cpp) | ||
if(TARGET ${PROJECT_NAME}-camera_common) | ||
target_link_libraries(${PROJECT_NAME}-camera_common ${PROJECT_NAME}) | ||
endif() | ||
|
||
ament_add_gtest(${PROJECT_NAME}-publisher test/test_publisher.cpp) | ||
if(TARGET ${PROJECT_NAME}-publisher) | ||
target_link_libraries(${PROJECT_NAME}-publisher ${PROJECT_NAME}) | ||
endif() | ||
|
||
ament_add_gtest(${PROJECT_NAME}-subscriber test/test_subscriber.cpp) | ||
if(TARGET ${PROJECT_NAME}-subscriber) | ||
target_link_libraries(${PROJECT_NAME}-subscriber ${PROJECT_NAME}) | ||
endif() | ||
|
||
ament_add_gtest(${PROJECT_NAME}-message_passing test/test_message_passing.cpp) | ||
if(TARGET ${PROJECT_NAME}-message_passing) | ||
target_link_libraries(${PROJECT_NAME}-message_passing ${PROJECT_NAME}) | ||
endif() | ||
|
||
ament_add_gtest(${PROJECT_NAME}-single_subscriber_publisher test/test_single_subscriber_publisher.cpp) | ||
if(TARGET ${PROJECT_NAME}-single_subscriber_publisher) | ||
target_link_libraries(${PROJECT_NAME}-single_subscriber_publisher ${PROJECT_NAME}) | ||
endif() | ||
endif() | ||
|
||
ament_package() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.