Skip to content

Commit

Permalink
Port to ROS 2 (#44)
Browse files Browse the repository at this point in the history
* Rename headers
Now with .hpp suffix

* Add linter tests

* Uncrustify

* Lint

* Do not run flake8 linter test

* Add LICENSE and CONTRIBUTING.md
This satisfies the ament_copyright linter.

* Fix deprecation warning

* Use rcutils log macro instead of custom macro

* Use tf2::BufferCoreInterface
Using this abstract interface enables use of the interactive marker client with other buffer implementations.
Also, switched to using shared pointers to avoid potential dangling reference.

* Replace 'init' topic with a ROS service
It seems more intuitive for clients to call a service to get the latest state for interactive
markers, versus subscribing to a latched topic and waiting for the server to publish.

* Add tests for InteractiveMarkerServer

* Add getter for client state
Useful for introspection, especially during testing.

* Add tests for InteractiveMarkerClient

* Merge SingleClient logic into InteractiveMarkerClient.
 Now it is assumed that there is maximum one server per client.
 This helps simplify the implementation.

* Update doc-block comment style

* Renaming of variables for clarity

* Remove old test code and unused single_client.hpp

* Refactor tools docs

* Remove notion of server ID

* Refactor interactive marker client docs

* Update copyright license

* Make shared library

* Add feedback publisher to client

* Implement client request timeout

If a response for the request isn't received within the provided timeout, then try again.

* Add logic for 'extrapolation into future' error

Rename custom exception and throw it in replace of tf2 exceptions.

* Default to C++14 and set stricter compiler flags
Fix compiler warnings

* Fix Windows compiler warnings

* Remove StateMachine class
The functionality it provided is not needed.

* Fix Clang warnings

* Move message context header into same directory as other headers

* Use visibility macros
  • Loading branch information
jacobperron committed Aug 30, 2019
1 parent 38b9777 commit 2b682ab
Show file tree
Hide file tree
Showing 40 changed files with 3,597 additions and 4,120 deletions.
133 changes: 79 additions & 54 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,67 +1,92 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(interactive_markers)
find_package(catkin REQUIRED
rosconsole
roscpp
rospy
rostest
std_msgs
tf
visualization_msgs
)
catkin_package(
INCLUDE_DIRS include
LIBRARIES interactive_markers
CATKIN_DEPENDS roscpp rosconsole rospy tf visualization_msgs
)
catkin_python_setup()

include_directories(include ${catkin_INCLUDE_DIRS})
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

add_library(${PROJECT_NAME}
src/interactive_marker_server.cpp
src/tools.cpp
src/menu_handler.cpp
src/interactive_marker_client.cpp
src/single_client.cpp
src/message_context.cpp
)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rmw REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)

add_library(${PROJECT_NAME} SHARED
src/interactive_marker_server.cpp
src/tools.cpp
src/menu_handler.cpp
src/interactive_marker_client.cpp
src/message_context.cpp
)
target_include_directories(${PROJECT_NAME} PUBLIC include)
ament_target_dependencies(${PROJECT_NAME}
"rclcpp"
"rmw"
"tf2"
"tf2_geometry_msgs"
"visualization_msgs")

install(TARGETS ${PROJECT_NAME}
DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
install(DIRECTORY include/interactive_markers/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h")
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

# C++ Unit Tests
#
if(CATKIN_ENABLE_TESTING)
include_directories(${GTEST_INCLUDE_DIRS})
install(
DIRECTORY include/
DESTINATION include)

add_executable(server_test EXCLUDE_FROM_ALL src/test/server_test.cpp)
target_link_libraries(server_test ${PROJECT_NAME} ${GTEST_LIBRARIES})
add_dependencies(tests server_test)
add_rostest(test/cpp_server.test)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME}
PRIVATE "INTERACTIVE_MARKERS_BUILDING_LIBRARY")

add_executable(client_test EXCLUDE_FROM_ALL src/test/client_test.cpp)
target_link_libraries(client_test ${PROJECT_NAME} ${GTEST_LIBRARIES})
add_dependencies(tests client_test)
add_rostest(test/cpp_client.test)
ament_export_dependencies("rclcpp")
ament_export_dependencies("rmw")
ament_export_dependencies("tf2")
ament_export_dependencies("tf2_geometry_msgs")
ament_export_dependencies("visualization_msgs")
ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})

add_executable(server_client_test EXCLUDE_FROM_ALL src/test/server_client_test.cpp)
target_link_libraries(server_client_test ${PROJECT_NAME} ${GTEST_LIBRARIES})
add_dependencies(tests server_client_test)
add_rostest(test/cpp_server_client.test)
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)

# Test program to simulate Interactive Marker with missing tf information
add_executable(bursty_tf EXCLUDE_FROM_ALL src/test/bursty_tf.cpp)
target_link_libraries(bursty_tf ${PROJECT_NAME})
add_dependencies(tests bursty_tf)
set(ament_cmake_flake8_FOUND TRUE)
ament_lint_auto_find_test_dependencies()

# Test program to simulate Interactive Marker with wrong tf information
add_executable(missing_tf EXCLUDE_FROM_ALL src/test/missing_tf.cpp)
target_link_libraries(missing_tf ${PROJECT_NAME})
add_dependencies(tests missing_tf)
ament_add_gtest(test_interactive_marker_server
test/${PROJECT_NAME}/test_interactive_marker_server.cpp
)
ament_target_dependencies(test_interactive_marker_server
"geometry_msgs"
"rclcpp"
"std_msgs"
)
target_link_libraries(test_interactive_marker_server
${PROJECT_NAME}
)

ament_add_gtest(test_interactive_marker_client
test/${PROJECT_NAME}/test_interactive_marker_client.cpp
)
ament_target_dependencies(test_interactive_marker_client
"geometry_msgs"
"rclcpp"
"std_msgs"
"tf2"
)
target_link_libraries(test_interactive_marker_client
${PROJECT_NAME}
)
endif()

ament_package()
3 changes: 3 additions & 0 deletions CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
Any contribution that you make to this repository will
be under the BSD license 2.0, as dictated by that
[license](https://opensource.org/licenses/BSD-3-Clause).
32 changes: 32 additions & 0 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
Copyright (c) 2012, Willow Garage, Inc.
Copyright (c) 2019, Open Source Robotics Foundation, Inc.
All rights reserved.

Software License Agreement (BSD License 2.0)

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:

* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above
copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided
with the distribution.
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
93 changes: 0 additions & 93 deletions include/interactive_markers/detail/message_context.h

This file was deleted.

Loading

0 comments on commit 2b682ab

Please sign in to comment.