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
16 changes: 12 additions & 4 deletions camera_info_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,10 +58,18 @@ if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

#TODO(mjcarroll) Enable unit test with rostest
#add_executable(unit_test tests/unit_test.cpp)
#target_link_libraries(unit_test ${PROJECT_NAME})
#add_rostest(tests/unit_test.test DEPENDENCIES unit_test)
ament_add_gtest(${PROJECT_NAME}-unit_test
tests/unit_test.cpp
WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}"
)
target_link_libraries(${PROJECT_NAME}-unit_test
${PROJECT_NAME}
${sensor_msgs_TARGETS}
rclcpp::rclcpp
)

# copy the file in the installation folder to test with package://
install(FILES tests/test_calibration.yaml DESTINATION share/${PROJECT_NAME}/tests)
endif()

ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -186,14 +186,14 @@ class CameraInfoManager
rclcpp::Node * node,
const std::string & cname = "camera",
const std::string & url = "",
const std::string & ns = "~");
const std::string & ns = "");

CAMERA_INFO_MANAGER_PUBLIC
CameraInfoManager(
rclcpp_lifecycle::LifecycleNode * node,
const std::string & cname = "camera",
const std::string & url = "",
const std::string & ns = "~");
const std::string & ns = "");

CAMERA_INFO_MANAGER_PUBLIC
CameraInfoManager(
Expand All @@ -202,7 +202,7 @@ class CameraInfoManager
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logger_interface,
const std::string & cname = "camera", const std::string & url = "",
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
const std::string & ns = "~");
const std::string & ns = "");

CAMERA_INFO_MANAGER_PUBLIC
CameraInfo getCameraInfo(void);
Expand Down
Loading