diff --git a/bitbots_behavior/bitbots_blackboard/CMakeLists.txt b/bitbots_behavior/bitbots_blackboard/CMakeLists.txt
index c363d76a8..9ae643437 100644
--- a/bitbots_behavior/bitbots_blackboard/CMakeLists.txt
+++ b/bitbots_behavior/bitbots_blackboard/CMakeLists.txt
@@ -1,81 +1,12 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_blackboard)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
-find_package(ament_cmake REQUIRED)
-find_package(bio_ik_msgs REQUIRED)
find_package(bitbots_docs REQUIRED)
-find_package(bitbots_msgs REQUIRED)
-find_package(geometry_msgs REQUIRED)
-find_package(rclpy REQUIRED)
-find_package(sensor_msgs REQUIRED)
-find_package(std_msgs REQUIRED)
-find_package(std_srvs REQUIRED)
-find_package(tf2 REQUIRED)
-find_package(tf2_geometry_msgs REQUIRED)
-
-set(INCLUDE_DIRS
- ${bio_ik_msgs_INCLUDE_DIRS}
- ${ament_cmake_INCLUDE_DIRS}
- ${sensor_msgs_INCLUDE_DIRS}
- ${rclpy_INCLUDE_DIRS}
- ${tf2_INCLUDE_DIRS}
- ${bitbots_msgs_INCLUDE_DIRS}
- ${std_msgs_INCLUDE_DIRS}
- ${tf2_geometry_msgs_INCLUDE_DIRS}
- ${std_srvs_INCLUDE_DIRS}
- ${geometry_msgs_INCLUDE_DIRS}
- ${bitbots_docs_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS
- ${bio_ik_msgs_LIBRARY_DIRS}
- ${ament_cmake_LIBRARY_DIRS}
- ${sensor_msgs_LIBRARY_DIRS}
- ${rclpy_LIBRARY_DIRS}
- ${tf2_LIBRARY_DIRS}
- ${bitbots_msgs_LIBRARY_DIRS}
- ${std_msgs_LIBRARY_DIRS}
- ${tf2_geometry_msgs_LIBRARY_DIRS}
- ${std_srvs_LIBRARY_DIRS}
- ${geometry_msgs_LIBRARY_DIRS}
- ${bitbots_docs_LIBRARY_DIRS})
-
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS
- ${bio_ik_msgs_LIBRARIES}
- ${ament_cmake_LIBRARIES}
- ${sensor_msgs_LIBRARIES}
- ${rclpy_LIBRARIES}
- ${tf2_LIBRARIES}
- ${bitbots_msgs_LIBRARIES}
- ${std_msgs_LIBRARIES}
- ${tf2_geometry_msgs_LIBRARIES}
- ${std_srvs_LIBRARIES}
- ${geometry_msgs_LIBRARIES}
- ${bitbots_docs_LIBRARIES})
+find_package(ament_cmake REQUIRED)
+find_package(ament_cmake_python REQUIRED)
-include(${CMAKE_BINARY_DIR}/../bitbots_docs/enable_bitbots_docs.cmake)
enable_bitbots_docs()
-ament_export_dependencies(bio_ik_msgs)
-ament_export_dependencies(ament_cmake)
-ament_export_dependencies(sensor_msgs)
-ament_export_dependencies(rclpy)
-ament_export_dependencies(tf2)
-ament_export_dependencies(bitbots_msgs)
-ament_export_dependencies(std_msgs)
-ament_export_dependencies(tf2_geometry_msgs)
-ament_export_dependencies(std_srvs)
-ament_export_dependencies(geometry_msgs)
-ament_export_dependencies(bitbots_docs)
-ament_export_include_directories(${INCLUDE_DIRS})
-
if(BUILD_TESTING)
find_package(ament_cmake_mypy REQUIRED)
ament_mypy(CONFIG_FILE "${CMAKE_CURRENT_LIST_DIR}/mypy.ini")
diff --git a/bitbots_lowlevel/bitbots_buttons/CMakeLists.txt b/bitbots_lowlevel/bitbots_buttons/CMakeLists.txt
index 5699cd0f5..771c19b29 100644
--- a/bitbots_lowlevel/bitbots_buttons/CMakeLists.txt
+++ b/bitbots_lowlevel/bitbots_buttons/CMakeLists.txt
@@ -6,6 +6,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
find_package(bitbots_docs REQUIRED)
diff --git a/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt b/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt
index a3fe26da8..65939952a 100644
--- a/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt
+++ b/bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt
@@ -6,6 +6,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
find_package(bitbots_buttons REQUIRED)
diff --git a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
index b49c2bf23..fb311c879 100644
--- a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
+++ b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
@@ -6,6 +6,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(backward_ros REQUIRED)
diff --git a/bitbots_misc/bitbots_basler_camera/package.xml b/bitbots_misc/bitbots_basler_camera/package.xml
index 1d7cc8afd..0dd36aaf0 100644
--- a/bitbots_misc/bitbots_basler_camera/package.xml
+++ b/bitbots_misc/bitbots_basler_camera/package.xml
@@ -12,6 +12,7 @@
Hamburg Bit-Bots
+ backward_ros
bitbots_docs
camera_info_manager
cv_bridge
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt b/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
index f08aaeb3d..f7c77480f 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
+++ b/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
@@ -6,16 +6,21 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
+find_package(ament_cmake REQUIRED)
+find_package(backward_ros REQUIRED)
+find_package(bitbots_docs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rclcpp REQUIRED)
-find_package(ament_cmake REQUIRED)
-find_package(tf2_ros REQUIRED)
+find_package(rot_conv REQUIRED)
find_package(std_msgs REQUIRED)
-find_package(tf2_geometry_msgs REQUIRED)
-find_package(bitbots_docs REQUIRED)
find_package(tf2 REQUIRED)
-find_package(rot_conv REQUIRED)
-find_package(backward_ros REQUIRED)
+find_package(tf2_geometry_msgs REQUIRED)
+find_package(tf2_ros REQUIRED)
add_compile_options(-Wall -Werror -Wno-unused)
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/package.xml b/bitbots_misc/bitbots_extrinsic_calibration/package.xml
index 1a8ec771e..07c816826 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/package.xml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/package.xml
@@ -9,17 +9,17 @@
Hamburg Bit-Bots
MIT
-
+
Florian Vahl
ament_cmake
+ backward_ros
bitbots_docs
+ rot_conv
std_msgs
- tf2
tf2_ros
- rot_conv
- backward_ros
+ tf2
diff --git a/bitbots_misc/bitbots_robot_description/CMakeLists.txt b/bitbots_misc/bitbots_robot_description/CMakeLists.txt
index 060c6f2ff..19767fabc 100644
--- a/bitbots_misc/bitbots_robot_description/CMakeLists.txt
+++ b/bitbots_misc/bitbots_robot_description/CMakeLists.txt
@@ -4,12 +4,6 @@ project(bitbots_robot_description)
find_package(bitbots_docs REQUIRED)
find_package(ament_cmake REQUIRED)
-set(INCLUDE_DIRS include)
-include_directories(${INCLUDE_DIRS})
-
-set(CMAKE_CXX_STANDARD 17)
-add_compile_options(-Wall -Werror -Wno-unused -pedantic -Wextra)
-
enable_bitbots_docs()
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_misc/bitbots_utils/CMakeLists.txt b/bitbots_misc/bitbots_utils/CMakeLists.txt
index 9a58212b3..1951ecba9 100644
--- a/bitbots_misc/bitbots_utils/CMakeLists.txt
+++ b/bitbots_misc/bitbots_utils/CMakeLists.txt
@@ -6,7 +6,13 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(bitbots_docs REQUIRED)
+find_package(backward_ros REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_python REQUIRED)
find_package(rclcpp REQUIRED)
@@ -26,7 +32,7 @@ add_compile_options(-Wall -Werror -Wno-unused -pedantic -Wextra -fPIC)
add_library(${PROJECT_NAME} src/utils.cpp)
# Add dependencies to cpp library
-ament_target_dependencies(${PROJECT_NAME} rclcpp tf2_ros)
+ament_target_dependencies(${PROJECT_NAME} rclcpp tf2_ros backward_ros)
ament_export_dependencies(rclcpp)
ament_export_include_directories(${INCLUDE_DIRS})
diff --git a/bitbots_misc/bitbots_utils/package.xml b/bitbots_misc/bitbots_utils/package.xml
index d2eb7babf..066879d4c 100644
--- a/bitbots_misc/bitbots_utils/package.xml
+++ b/bitbots_misc/bitbots_utils/package.xml
@@ -11,11 +11,12 @@
Hamburg Bit-Bots
MIT
-
+
Hamburg Bit-Bots
ament_cmake
+ backward_ros
bitbots_docs
python3-yaml
python3-transforms3d
diff --git a/bitbots_motion/bitbots_dynamic_kick/CMakeLists.txt b/bitbots_motion/bitbots_dynamic_kick/CMakeLists.txt
index fb4787aed..e9ca70b50 100644
--- a/bitbots_motion/bitbots_dynamic_kick/CMakeLists.txt
+++ b/bitbots_motion/bitbots_dynamic_kick/CMakeLists.txt
@@ -6,9 +6,15 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
-find_package(bitbots_docs REQUIRED)
+find_package(backward_ros REQUIRED)
find_package(biped_interfaces REQUIRED)
+find_package(bitbots_docs REQUIRED)
find_package(bitbots_msgs REQUIRED)
find_package(bitbots_splines REQUIRED)
find_package(control_msgs REQUIRED)
@@ -25,7 +31,6 @@ find_package(tf2 REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
-find_package(backward_ros REQUIRED)
find_package(PythonLibs COMPONENTS Interpreter Development)
diff --git a/bitbots_motion/bitbots_dynup/CMakeLists.txt b/bitbots_motion/bitbots_dynup/CMakeLists.txt
index 5760b5ce0..e64bcbc9c 100644
--- a/bitbots_motion/bitbots_dynup/CMakeLists.txt
+++ b/bitbots_motion/bitbots_dynup/CMakeLists.txt
@@ -6,6 +6,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 20)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
set(PYBIND11_PYTHON_VERSION 3)
set(PYBIND11_FINDPYTHON ON)
diff --git a/bitbots_motion/bitbots_hcm/CMakeLists.txt b/bitbots_motion/bitbots_hcm/CMakeLists.txt
index 4fa8c90a9..4fd72f3cd 100644
--- a/bitbots_motion/bitbots_hcm/CMakeLists.txt
+++ b/bitbots_motion/bitbots_hcm/CMakeLists.txt
@@ -1,6 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_hcm)
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
set(PYBIND11_PYTHON_VERSION 3)
set(PYBIND11_FINDPYTHON ON)
find_package(ament_cmake REQUIRED)
@@ -19,7 +24,7 @@ find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
- add_compile_options(-fvisibility=hidden)
+ add_compile_options(-fvisibility=hidden -Wall -Wextra -Wpedantic)
endif()
include_directories(${PYTHON_INCLUDE_DIRS})
diff --git a/bitbots_motion/bitbots_head_mover/CMakeLists.txt b/bitbots_motion/bitbots_head_mover/CMakeLists.txt
index 3fa26761b..eafa503d9 100644
--- a/bitbots_motion/bitbots_head_mover/CMakeLists.txt
+++ b/bitbots_motion/bitbots_head_mover/CMakeLists.txt
@@ -1,6 +1,11 @@
cmake_minimum_required(VERSION 3.8)
project(bitbots_head_mover)
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
@@ -12,7 +17,6 @@ find_package(bio_ik REQUIRED)
find_package(bio_ik_msgs REQUIRED)
find_package(bitbots_msgs REQUIRED)
find_package(generate_parameter_library REQUIRED)
-find_package(bitbots_msgs REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(moveit_ros_planning REQUIRED)
@@ -23,8 +27,6 @@ find_package(std_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
-set(CMAKE_BUILD_TYPE Debug)
-
# uncomment the following section in order to fill in further dependencies
# manually. find_package( REQUIRED)
generate_parameter_library(
diff --git a/bitbots_motion/bitbots_moveit_bindings/CMakeLists.txt b/bitbots_motion/bitbots_moveit_bindings/CMakeLists.txt
index 08708a75c..4d90c35e7 100644
--- a/bitbots_motion/bitbots_moveit_bindings/CMakeLists.txt
+++ b/bitbots_motion/bitbots_moveit_bindings/CMakeLists.txt
@@ -6,24 +6,29 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
set(PYBIND11_PYTHON_VERSION 3)
set(PYBIND11_FINDPYTHON ON)
-find_package(bitbots_docs REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
find_package(bio_ik REQUIRED)
find_package(bio_ik_msgs REQUIRED)
+find_package(bitbots_docs REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_msgs REQUIRED)
-find_package(moveit_ros_planning_interface REQUIRED)
find_package(moveit_ros_planning REQUIRED)
+find_package(moveit_ros_planning_interface REQUIRED)
find_package(pybind11 REQUIRED)
find_package(Python3 REQUIRED COMPONENTS Interpreter Development)
+find_package(rclcpp REQUIRED)
find_package(ros2_python_extension)
find_package(tf2 REQUIRED)
-find_package(tf2_ros REQUIRED)
find_package(tf2_kdl REQUIRED)
-find_package(rclcpp REQUIRED)
+find_package(tf2_ros REQUIRED)
add_compile_options(-Wall -Wno-unused)
diff --git a/bitbots_motion/bitbots_moveit_bindings/package.xml b/bitbots_motion/bitbots_moveit_bindings/package.xml
index 3b7312d36..0353a9065 100644
--- a/bitbots_motion/bitbots_moveit_bindings/package.xml
+++ b/bitbots_motion/bitbots_moveit_bindings/package.xml
@@ -10,16 +10,16 @@
MIT
ament_cmake
- bitbots_docs
- bio_ik
+ backward_ros
bio_ik_msgs
+ bio_ik
+ bitbots_docs
moveit_core
- moveit_ros_planning
moveit_ros_planning_interface
+ moveit_ros_planning
pybind11_vendor
ros2_python_extension
-
- ament_cmake
+ ament_cmake
diff --git a/bitbots_motion/bitbots_quintic_walk/CMakeLists.txt b/bitbots_motion/bitbots_quintic_walk/CMakeLists.txt
index 7a4f5637a..818f1d42a 100644
--- a/bitbots_motion/bitbots_quintic_walk/CMakeLists.txt
+++ b/bitbots_motion/bitbots_quintic_walk/CMakeLists.txt
@@ -6,6 +6,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 20)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
set(PYBIND11_PYTHON_VERSION 3)
set(PYBIND11_FINDPYTHON ON)
find_package(ament_cmake REQUIRED)
diff --git a/bitbots_motion/bitbots_rl_motion/CMakeLists.txt b/bitbots_motion/bitbots_rl_motion/CMakeLists.txt
index 78ed31086..7f83a4899 100644
--- a/bitbots_motion/bitbots_rl_motion/CMakeLists.txt
+++ b/bitbots_motion/bitbots_rl_motion/CMakeLists.txt
@@ -1,37 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_rl_motion)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
-find_package(rclpy REQUIRED)
-find_package(std_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(bitbots_docs REQUIRED)
-set(INCLUDE_DIRS ${rclpy_INCLUDE_DIRS} ${std_msgs_INCLUDE_DIRS}
- ${ament_cmake_INCLUDE_DIRS} ${bitbots_docs_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS ${rclpy_LIBRARY_DIRS} ${std_msgs_LIBRARY_DIRS}
- ${ament_cmake_LIBRARY_DIRS} ${bitbots_docs_LIBRARY_DIRS})
-
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS ${rclpy_LIBRARIES} ${std_msgs_LIBRARIES} ${ament_cmake_LIBRARIES}
- ${bitbots_docs_LIBRARIES})
-
-include(${CMAKE_BINARY_DIR}/../bitbots_docs/enable_bitbots_docs.cmake)
enable_bitbots_docs()
-ament_export_dependencies(rclpy)
-ament_export_dependencies(std_msgs)
-ament_export_dependencies(ament_cmake)
-ament_export_dependencies(bitbots_docs)
-ament_export_include_directories(${INCLUDE_DIRS})
-
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY rl_walk_models DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_motion/bitbots_splines/CMakeLists.txt b/bitbots_motion/bitbots_splines/CMakeLists.txt
index dc1b991d5..ae1098145 100644
--- a/bitbots_motion/bitbots_splines/CMakeLists.txt
+++ b/bitbots_motion/bitbots_splines/CMakeLists.txt
@@ -6,16 +6,22 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
+find_package(backward_ros REQUIRED)
find_package(bitbots_docs REQUIRED)
-find_package(rclcpp REQUIRED)
-find_package(std_msgs REQUIRED)
+find_package(Eigen3 REQUIRED)
find_package(geometry_msgs REQUIRED)
-find_package(tf2_geometry_msgs REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_ros_planning REQUIRED)
-find_package(Eigen3 REQUIRED)
find_package(PkgConfig REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(std_msgs REQUIRED)
+find_package(tf2_geometry_msgs REQUIRED)
set(INCLUDE_DIRS include)
include_directories(${INCLUDE_DIRS})
@@ -38,6 +44,7 @@ add_library(${PROJECT_NAME} SHARED ${SOURCES})
ament_target_dependencies(
${PROJECT_NAME}
ament_cmake
+ backward_ros
bitbots_docs
rclcpp
std_msgs
diff --git a/bitbots_motion/bitbots_splines/package.xml b/bitbots_motion/bitbots_splines/package.xml
index d73d3a817..3d0966b98 100644
--- a/bitbots_motion/bitbots_splines/package.xml
+++ b/bitbots_motion/bitbots_splines/package.xml
@@ -16,15 +16,16 @@
ament_cmake
- std_msgs
- geometry_msgs
+ backward_ros
bitbots_docs
- rclcpp
- tf2_geometry_msgs
+ eigen
+ geometry_msgs
moveit_core
moveit_ros_planning
- eigen
python3-matplotlib
+ rclcpp
+ std_msgs
+ tf2_geometry_msgs
diff --git a/bitbots_msgs/CMakeLists.txt b/bitbots_msgs/CMakeLists.txt
index 74c50a259..90ec230d9 100644
--- a/bitbots_msgs/CMakeLists.txt
+++ b/bitbots_msgs/CMakeLists.txt
@@ -1,6 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_msgs)
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(action_msgs REQUIRED)
diff --git a/bitbots_navigation/bitbots_localization/CMakeLists.txt b/bitbots_navigation/bitbots_localization/CMakeLists.txt
index 841ccfd7a..4eadc1f07 100644
--- a/bitbots_navigation/bitbots_localization/CMakeLists.txt
+++ b/bitbots_navigation/bitbots_localization/CMakeLists.txt
@@ -6,6 +6,11 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(backward_ros REQUIRED)
diff --git a/bitbots_navigation/bitbots_odometry/CMakeLists.txt b/bitbots_navigation/bitbots_odometry/CMakeLists.txt
index 9ff8c552c..90e8feefe 100644
--- a/bitbots_navigation/bitbots_odometry/CMakeLists.txt
+++ b/bitbots_navigation/bitbots_odometry/CMakeLists.txt
@@ -6,7 +6,13 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
+# Build with release optimizations and debug symbols by default
+if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
+ set(CMAKE_BUILD_TYPE RelWithDebug)
+endif()
+
find_package(ament_cmake REQUIRED)
+find_package(backward_ros REQUIRED)
find_package(biped_interfaces REQUIRED)
find_package(bitbots_docs REQUIRED)
find_package(bitbots_utils REQUIRED)
@@ -39,6 +45,7 @@ target_link_libraries(motion_odometry rclcpp::rclcpp odometry_parameters)
ament_target_dependencies(
motion_odometry
ament_cmake
+ backward_ros
biped_interfaces
bitbots_docs
bitbots_utils
@@ -57,6 +64,7 @@ ament_target_dependencies(
ament_target_dependencies(
odometry_fuser
ament_cmake
+ backward_ros
biped_interfaces
bitbots_docs
bitbots_utils
diff --git a/bitbots_navigation/bitbots_odometry/package.xml b/bitbots_navigation/bitbots_odometry/package.xml
index c3db876be..ea39d7b19 100644
--- a/bitbots_navigation/bitbots_odometry/package.xml
+++ b/bitbots_navigation/bitbots_odometry/package.xml
@@ -14,6 +14,7 @@
Jasper Güldenstein
ament_cmake
+ backward_ros
biped_interfaces
bitbots_docs
bitbots_utils
diff --git a/bitbots_robot/wolfgang_animations/CMakeLists.txt b/bitbots_robot/wolfgang_animations/CMakeLists.txt
index 309f55468..79500c36a 100644
--- a/bitbots_robot/wolfgang_animations/CMakeLists.txt
+++ b/bitbots_robot/wolfgang_animations/CMakeLists.txt
@@ -1,28 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(wolfgang_animations)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
find_package(ament_cmake REQUIRED)
+find_package(bitbots_docs REQUIRED)
-set(INCLUDE_DIRS ${ament_cmake_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS ${ament_cmake_LIBRARY_DIRS})
-
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS ${ament_cmake_LIBRARIES})
-
-include(${CMAKE_BINARY_DIR}/../bitbots_docs/enable_bitbots_docs.cmake)
enable_bitbots_docs()
-ament_export_dependencies(ament_cmake)
-ament_export_include_directories(${INCLUDE_DIRS})
-
install(DIRECTORY animations DESTINATION share/${PROJECT_NAME})
ament_package()
diff --git a/bitbots_robot/wolfgang_description/CMakeLists.txt b/bitbots_robot/wolfgang_description/CMakeLists.txt
index 7cfdeef37..499116a42 100644
--- a/bitbots_robot/wolfgang_description/CMakeLists.txt
+++ b/bitbots_robot/wolfgang_description/CMakeLists.txt
@@ -1,61 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(wolfgang_description)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
find_package(bitbots_docs REQUIRED)
-find_package(urdf REQUIRED)
-find_package(xacro REQUIRED)
-find_package(sensor_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
-find_package(tf2 REQUIRED)
-find_package(rclcpp REQUIRED)
-
-set(INCLUDE_DIRS
- ${bitbots_docs_INCLUDE_DIRS}
- ${urdf_INCLUDE_DIRS}
- ${xacro_INCLUDE_DIRS}
- ${sensor_msgs_INCLUDE_DIRS}
- ${ament_cmake_INCLUDE_DIRS}
- ${tf2_INCLUDE_DIRS}
- ${rclcpp_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS
- ${bitbots_docs_LIBRARY_DIRS}
- ${urdf_LIBRARY_DIRS}
- ${xacro_LIBRARY_DIRS}
- ${sensor_msgs_LIBRARY_DIRS}
- ${ament_cmake_LIBRARY_DIRS}
- ${tf2_LIBRARY_DIRS}
- ${rclcpp_LIBRARY_DIRS})
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS
- ${bitbots_docs_LIBRARIES}
- ${urdf_LIBRARIES}
- ${xacro_LIBRARIES}
- ${sensor_msgs_LIBRARIES}
- ${ament_cmake_LIBRARIES}
- ${tf2_LIBRARIES}
- ${rclcpp_LIBRARIES})
-
-include(${CMAKE_BINARY_DIR}/../bitbots_docs/enable_bitbots_docs.cmake)
enable_bitbots_docs()
-ament_export_dependencies(bitbots_docs)
-ament_export_dependencies(urdf)
-ament_export_dependencies(xacro)
-ament_export_dependencies(sensor_msgs)
-ament_export_dependencies(ament_cmake)
-ament_export_dependencies(tf2)
-ament_export_dependencies(rclcpp)
-ament_export_include_directories(${INCLUDE_DIRS})
-
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY urdf DESTINATION share/${PROJECT_NAME})
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_robot/wolfgang_moveit_config/CMakeLists.txt b/bitbots_robot/wolfgang_moveit_config/CMakeLists.txt
index 6c20803ab..335eb9db8 100644
--- a/bitbots_robot/wolfgang_moveit_config/CMakeLists.txt
+++ b/bitbots_robot/wolfgang_moveit_config/CMakeLists.txt
@@ -1,26 +1,10 @@
cmake_minimum_required(VERSION 3.5)
project(wolfgang_moveit_config)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
find_package(ament_cmake REQUIRED)
+find_package(bitbots_docs REQUIRED)
-set(INCLUDE_DIRS ${ament_cmake_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS ${ament_cmake_LIBRARY_DIRS})
-
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS ${ament_cmake_LIBRARIES})
-
-install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
-
-ament_export_dependencies(ament_cmake)
-ament_export_include_directories(${INCLUDE_DIRS})
+enable_bitbots_docs()
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_robot/wolfgang_moveit_config/docs/_static/logo.png b/bitbots_robot/wolfgang_moveit_config/docs/_static/logo.png
new file mode 100644
index 000000000..f8afdd5d0
Binary files /dev/null and b/bitbots_robot/wolfgang_moveit_config/docs/_static/logo.png differ
diff --git a/bitbots_robot/wolfgang_moveit_config/docs/conf.py b/bitbots_robot/wolfgang_moveit_config/docs/conf.py
new file mode 100644
index 000000000..0b6342a9c
--- /dev/null
+++ b/bitbots_robot/wolfgang_moveit_config/docs/conf.py
@@ -0,0 +1,187 @@
+#
+# Full list of options at http://www.sphinx-doc.org/en/master/config
+
+# -- Path setup --------------------------------------------------------------
+
+# If extensions (or modules to document with autodoc) are in another directory,
+# add these directories to sys.path here. If the directory is relative to the
+# documentation root, use os.path.abspath to make it absolute, like shown here.
+#
+import os
+import sys
+
+import catkin_pkg.package
+from exhale import utils
+
+package_dir = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))
+catkin_package = catkin_pkg.package.parse_package(
+ os.path.join(package_dir, catkin_pkg.package.PACKAGE_MANIFEST_FILENAME)
+)
+sys.path.insert(0, os.path.abspath(os.path.join(package_dir, "src")))
+
+
+# -- Helper functions --------------------------------------------------------
+
+
+def count_files():
+ """:returns tuple of (num_py, num_cpp)"""
+ num_py = 0
+ num_cpp = 0
+
+ for _, _, files in os.walk(os.path.join(package_dir, "src")):
+ for f in files:
+ if f.endswith(".py"):
+ num_py += 1
+ for _, _, files in os.walk(os.path.join(package_dir, "include")):
+ for f in files:
+ if f.endswith(".h") or f.endswith(".hpp"):
+ num_cpp += 1
+
+ return num_py, num_cpp
+
+
+# -- Project information -----------------------------------------------------
+
+project = catkin_package.name
+copyright = "2019, Bit-Bots"
+author = ", ".join([a.name for a in catkin_package.authors])
+
+# The short X.Y version
+version = str(catkin_package.version)
+# The full version, including alpha/beta/rc tags
+release = str(catkin_package.version)
+
+# -- General configuration ---------------------------------------------------
+
+# If your documentation needs a minimal Sphinx version, state it here.
+#
+# needs_sphinx = '1.0'
+
+# Add any Sphinx extension module names here, as strings. They can be
+# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom
+# ones.
+extensions = [
+ "sphinx.ext.autodoc",
+ "sphinx.ext.doctest",
+ "sphinx.ext.intersphinx",
+ "sphinx.ext.todo",
+ "sphinx.ext.coverage",
+ "sphinx.ext.imgmath",
+ "sphinx.ext.viewcode",
+ "sphinx_rtd_theme",
+]
+
+# Add any paths that contain templates here, relative to this directory.
+templates_path = ["_templates"]
+
+# The suffix(es) of source filenames.
+# You can specify multiple suffix as a list of string:
+#
+# source_suffix = ['.rst', '.md']
+source_suffix = ".rst"
+
+# The master toctree document.
+master_doc = "index"
+
+# The language for content autogenerated by Sphinx. Refer to documentation
+# for a list of supported languages.
+#
+# This is also used if you do content translation via gettext catalogs.
+# Usually you set "language" from the command line for these cases.
+language = None
+
+# List of patterns, relative to source directory, that match files and
+# directories to ignore when looking for source files.
+# This pattern also affects html_static_path and html_extra_path.
+exclude_patterns = ["_build", "Thumbs.db", ".DS_Store"]
+
+# The name of the Pygments (syntax highlighting) style to use.
+pygments_style = None
+
+# -- Exhale and Breath setup -------------------------------------------------
+
+# Tell sphinx what the primary language being documented is.
+num_files_py, num_files_cpp = count_files()
+primary_domain = "py" if num_files_py >= num_files_cpp else "cpp"
+
+# Tell sphinx what the pygments highlight language should be.
+highlight_language = primary_domain
+
+if num_files_cpp > 0:
+ extensions += [
+ "breathe",
+ "exhale",
+ ]
+
+ breathe_projects = {project: os.path.join("_build", "doxyoutput", "xml")}
+ breathe_default_project = project
+
+ def specifications_for_kind(kind):
+ # Show all members for classes and structs
+ if kind == "class" or kind == "struct":
+ return [":members:", ":protected-members:", ":private-members:", ":undoc-members:"]
+ # An empty list signals to Exhale to use the defaults
+ else:
+ return []
+
+ exhale_args = {
+ # These arguments are required
+ "containmentFolder": "cppapi",
+ "rootFileName": "library_root.rst",
+ "rootFileTitle": "C++ Library API",
+ "doxygenStripFromPath": "..",
+ "customSpecificationsMapping": utils.makeCustomSpecificationsMapping(specifications_for_kind),
+ # Suggested optional arguments
+ "createTreeView": True,
+ "exhaleExecutesDoxygen": True,
+ "exhaleDoxygenStdin": "INPUT = {}".format(os.path.join(package_dir, "include")),
+ }
+
+# -- Options for HTML output -------------------------------------------------
+
+# The theme to use for HTML and HTML Help pages. See the documentation for
+# a list of builtin themes.
+#
+html_theme = "sphinx_rtd_theme"
+
+# Theme options are theme-specific and customize the look and feel of a theme
+# further. For a list of options available for each theme, see the
+# documentation.
+#
+# html_theme_options = {}
+
+# Add any paths that contain custom static files (such as style sheets) here,
+# relative to this directory. They are copied after the builtin static files,
+# so a file named "default.css" will overwrite the builtin "default.css".
+html_static_path = ["_static"]
+
+# Custom sidebar templates, must be a dictionary that maps document names
+# to template names.
+#
+# The default sidebars (for documents that don't match any pattern) are
+# defined by theme itself. Builtin themes are using these templates by
+# default: ``['localtoc.html', 'relations.html', 'sourcelink.html',
+# 'searchbox.html']``.
+#
+# html_sidebars = {}
+
+html_logo = os.path.join("_static", "logo.png")
+html_favicon = os.path.join("_static", "logo.png")
+
+
+# -- Options for intersphinx extension ---------------------------------------
+
+# Example configuration for intersphinx: refer to the Python standard library.
+intersphinx_mapping = {"https://docs.python.org/": None}
+
+# -- Options for todo extension ----------------------------------------------
+
+# If true, `todo` and `todoList` produce output, else they produce nothing.
+todo_include_todos = True
+
+# -- RST Standard variables ---------------------------------------------------
+rst_prolog = f".. |project| replace:: {project}\n"
+rst_prolog += ".. |description| replace:: {}\n".format(catkin_package.description.replace("\n\n", "\n"))
+rst_prolog += ".. |modindex| replace:: {}\n".format(
+ ":ref:`modindex`" if num_files_py > 0 else "Python module index is not available"
+)
diff --git a/bitbots_robot/wolfgang_moveit_config/docs/index.rst b/bitbots_robot/wolfgang_moveit_config/docs/index.rst
new file mode 100644
index 000000000..e76aa433a
--- /dev/null
+++ b/bitbots_robot/wolfgang_moveit_config/docs/index.rst
@@ -0,0 +1,21 @@
+Welcome to |project|'s documentation!
+================================================
+
+Description
+-----------
+
+|description|
+
+.. toctree::
+ :maxdepth: 2
+
+ cppapi/library_root
+ pyapi/modules
+
+
+Indices and tables
+==================
+
+* :ref:`genindex`
+* |modindex|
+* :ref:`search`
diff --git a/bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt b/bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt
index 8bf69dfe2..fa96b424b 100644
--- a/bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt
+++ b/bitbots_simulation/bitbots_pybullet_sim/CMakeLists.txt
@@ -1,71 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_pybullet_sim)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
-find_package(nav_msgs REQUIRED)
-find_package(rclpy REQUIRED)
-find_package(sensor_msgs REQUIRED)
-find_package(urdf REQUIRED)
-find_package(bitbots_msgs REQUIRED)
-find_package(rosgraph_msgs REQUIRED)
-find_package(bitbots_docs REQUIRED)
-find_package(std_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
+find_package(bitbots_docs REQUIRED)
-set(INCLUDE_DIRS
- ${nav_msgs_INCLUDE_DIRS}
- ${rclpy_INCLUDE_DIRS}
- ${sensor_msgs_INCLUDE_DIRS}
- ${urdf_INCLUDE_DIRS}
- ${bitbots_msgs_INCLUDE_DIRS}
- ${rosgraph_msgs_INCLUDE_DIRS}
- ${bitbots_docs_INCLUDE_DIRS}
- ${std_msgs_INCLUDE_DIRS}
- ${ament_cmake_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS
- ${nav_msgs_LIBRARY_DIRS}
- ${rclpy_LIBRARY_DIRS}
- ${sensor_msgs_LIBRARY_DIRS}
- ${urdf_LIBRARY_DIRS}
- ${bitbots_msgs_LIBRARY_DIRS}
- ${rosgraph_msgs_LIBRARY_DIRS}
- ${bitbots_docs_LIBRARY_DIRS}
- ${std_msgs_LIBRARY_DIRS}
- ${ament_cmake_LIBRARY_DIRS})
-
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS
- ${nav_msgs_LIBRARIES}
- ${rclpy_LIBRARIES}
- ${sensor_msgs_LIBRARIES}
- ${urdf_LIBRARIES}
- ${bitbots_msgs_LIBRARIES}
- ${rosgraph_msgs_LIBRARIES}
- ${bitbots_docs_LIBRARIES}
- ${std_msgs_LIBRARIES}
- ${ament_cmake_LIBRARIES})
-
-include(${CMAKE_BINARY_DIR}/../bitbots_docs/enable_bitbots_docs.cmake)
enable_bitbots_docs()
-ament_export_dependencies(nav_msgs)
-ament_export_dependencies(rclpy)
-ament_export_dependencies(sensor_msgs)
-ament_export_dependencies(urdf)
-ament_export_dependencies(bitbots_msgs)
-ament_export_dependencies(rosgraph_msgs)
-ament_export_dependencies(bitbots_docs)
-ament_export_dependencies(std_msgs)
-ament_export_dependencies(ament_cmake)
-ament_export_include_directories(${INCLUDE_DIRS})
-
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY models DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_simulation/bitbots_pybullet_sim/src/bitbots_pybullet_sim/ros_interface.py b/bitbots_simulation/bitbots_pybullet_sim/src/bitbots_pybullet_sim/ros_interface.py
deleted file mode 100644
index 01554c1f2..000000000
--- a/bitbots_simulation/bitbots_pybullet_sim/src/bitbots_pybullet_sim/ros_interface.py
+++ /dev/null
@@ -1,283 +0,0 @@
-import time
-
-import rospy
-from geometry_msgs.msg import PointStamped
-from nav_msgs.msg import Odometry
-from rosgraph_msgs.msg import Clock
-from sensor_msgs.msg import Imu, JointState
-from std_msgs.msg import Bool, Float32
-from tf.transformations import euler_from_quaternion
-
-from bitbots_msgs.msg import FootPressure, JointCommand
-
-
-class ROSInterface:
- def __init__(self, simulation, namespace="", node=True):
- self.namespace = namespace
- # give possibility to use the interface directly as class with setting node=False
- if node:
- if namespace == "":
- rospy.init_node("pybullet_sim")
- else:
- rospy.init_node("pybullet_sim", anonymous=True, argv=["clock:=/" + self.namespace + "/clock"])
-
- self.simulation = simulation
- self.namespace = namespace
- self.last_time = time.time()
- self.last_linear_vel = (0, 0, 0)
-
- # messages
- self.real_time_msg = Float32()
- self.joint_state_msg = JointState()
- self.joint_state_msg.header.frame_id = "base_link"
- self.joint_state_msg.name = self.simulation.get_joint_names()
- self.imu_msg = Imu()
- self.imu_msg.header.frame_id = "imu_frame"
- self.clock_msg = Clock()
- self.foot_msg_left = FootPressure()
- self.foot_msg_left.header.frame_id = "l_sole"
- self.foot_msg_right = FootPressure()
- self.foot_msg_right.header.frame_id = "r_sole"
- self.odom_msg = Odometry()
- self.odom_msg.header.frame_id = "odom"
- self.odom_msg.child_frame_id = "base_link"
- # we just use the first robot
- self.robot_index = self.simulation.robot_indexes[0]
-
- # publisher
- self.left_foot_pressure_publisher = rospy.Publisher(
- self.namespace + "foot_pressure_left/raw", FootPressure, queue_size=1
- )
- self.right_foot_pressure_publisher = rospy.Publisher(
- self.namespace + "foot_pressure_right/raw", FootPressure, queue_size=1
- )
- self.left_foot_pressure_publisher_filtered = rospy.Publisher(
- self.namespace + "foot_pressure_left/filtered", FootPressure, queue_size=1
- )
- self.right_foot_pressure_publisher_filtered = rospy.Publisher(
- self.namespace + "foot_pressure_right/filtered", FootPressure, queue_size=1
- )
- self.joint_publisher = rospy.Publisher(self.namespace + "joint_states", JointState, queue_size=1)
- self.imu_publisher = rospy.Publisher(self.namespace + "imu/data_raw", Imu, queue_size=1)
- self.clock_publisher = rospy.Publisher(self.namespace + "clock", Clock, queue_size=1)
- self.real_time_factor_publisher = rospy.Publisher(self.namespace + "real_time_factor", Float32, queue_size=1)
- self.true_odom_publisher = rospy.Publisher(self.namespace + "true_odom", Odometry, queue_size=1)
- self.cop_l_pub_ = rospy.Publisher(self.namespace + "cop_l", PointStamped, queue_size=1)
- self.cop_r_pub_ = rospy.Publisher(self.namespace + "cop_r", PointStamped, queue_size=1)
-
- # subscriber
- self.joint_goal_subscriber = rospy.Subscriber(
- self.namespace + "DynamixelController/command",
- JointCommand,
- self.joint_goal_cb,
- queue_size=1,
- tcp_nodelay=True,
- )
-
- self.reset_subscriber = rospy.Subscriber(
- self.namespace + "reset", Bool, self.reset_cb, queue_size=1, tcp_nodelay=True
- )
-
- def step(self):
- self.simulation.step()
- self.publish_joints()
- self.publish_imu()
- self.publish_foot_pressure()
- self.publish_true_odom()
- self.clock_msg.clock = rospy.Time.from_seconds(self.simulation.time)
- self.clock_publisher.publish(self.clock_msg)
- self.compute_real_time_factor()
-
- def run_simulation(self, duration=None, sleep=0):
- start_time = rospy.get_time()
- while not rospy.is_shutdown() and (duration is None or rospy.get_time() - start_time < duration):
- self.step()
- time.sleep(sleep)
-
- def compute_real_time_factor(self):
- time_now = time.time()
- self.real_time_msg.data = self.simulation.timestep / (time_now - self.last_time)
- self.last_time = time_now
- self.real_time_factor_publisher.publish(self.real_time_msg)
-
- def get_joint_state_msg(self):
- positions = []
- velocities = []
- efforts = []
- for name in self.joint_state_msg.name:
- joint = self.simulation.joints[self.robot_index][name]
- # this is necessary to update the joint state
- # it is not done automatically in the simulation step, since we might not need this info
- joint.update()
- position, velocity, forces, applied_torque = joint.get_state()
- positions.append(position)
- velocities.append(velocity)
- efforts.append(applied_torque)
- self.joint_state_msg.position = positions
- self.joint_state_msg.velocity = velocities
- self.joint_state_msg.effort = efforts
- self.joint_state_msg.header.stamp = rospy.Time.from_seconds(self.simulation.time)
- return self.joint_state_msg
-
- def publish_joints(self):
- self.joint_publisher.publish(self.get_joint_state_msg())
-
- def get_imu_msg(self):
- orientation = self.simulation.get_imu_quaternion()
- self.imu_msg.orientation.x = orientation[0]
- self.imu_msg.orientation.y = orientation[1]
- self.imu_msg.orientation.z = orientation[2]
- self.imu_msg.orientation.w = orientation[3]
- linear_vel, angular_vel = self.simulation.get_robot_velocity()
- self.imu_msg.angular_velocity.x = angular_vel[0]
- self.imu_msg.angular_velocity.y = angular_vel[1]
- self.imu_msg.angular_velocity.z = angular_vel[2]
- # simple acceleration computation by using diff of velocities
- linear_acc = tuple(map(lambda i, j: i - j, self.last_linear_vel, linear_vel))
- self.last_linear_vel = linear_vel
- # adding gravity to the acceleration
- r, p, y = euler_from_quaternion(orientation)
- gravity = [r * 9.81, p * 9.81, y * 9.81]
- linear_acc = tuple([linear_acc[0] + gravity[0], linear_acc[1] + gravity[1], linear_acc[2] + gravity[2]])
- self.imu_msg.linear_acceleration.x = linear_acc[0]
- self.imu_msg.linear_acceleration.y = linear_acc[1]
- self.imu_msg.linear_acceleration.z = linear_acc[2]
- self.imu_msg.header.stamp = rospy.Time.from_seconds(self.simulation.time)
- return self.imu_msg
-
- def publish_imu(self):
- self.imu_publisher.publish(self.get_imu_msg())
-
- def get_pressure_filtered_left(self):
- if len(self.simulation.pressure_sensors) == 0:
- rospy.logwarn_once("No pressure sensors found in simulation model")
- return self.foot_msg_left
- f_llb = self.simulation.pressure_sensors[self.robot_index]["LLB"].get_force()
- f_llf = self.simulation.pressure_sensors[self.robot_index]["LLF"].get_force()
- f_lrf = self.simulation.pressure_sensors[self.robot_index]["LRF"].get_force()
- f_lrb = self.simulation.pressure_sensors[self.robot_index]["LRB"].get_force()
- self.foot_msg_left.left_back = f_llb[1]
- self.foot_msg_left.left_front = f_llf[1]
- self.foot_msg_left.right_front = f_lrf[1]
- self.foot_msg_left.right_back = f_lrb[1]
- return self.foot_msg_left
-
- def get_pressure_filtered_right(self):
- if len(self.simulation.pressure_sensors) == 0:
- rospy.logwarn_once("No pressure sensors found in simulation model")
- return self.foot_msg_right
- f_rlb = self.simulation.pressure_sensors[self.robot_index]["RLB"].get_force()
- f_rlf = self.simulation.pressure_sensors[self.robot_index]["RLF"].get_force()
- f_rrf = self.simulation.pressure_sensors[self.robot_index]["RRF"].get_force()
- f_rrb = self.simulation.pressure_sensors[self.robot_index]["RRB"].get_force()
- self.foot_msg_right.left_back = f_rlb[1]
- self.foot_msg_right.left_front = f_rlf[1]
- self.foot_msg_right.right_front = f_rrf[1]
- self.foot_msg_right.right_back = f_rrb[1]
- return self.foot_msg_right
-
- def publish_foot_pressure(self):
- # some models dont have sensors
- if len(self.simulation.pressure_sensors) == 0:
- rospy.logwarn_once("No pressure sensors found in simulation model")
- return
-
- f_llb = self.simulation.pressure_sensors[self.robot_index]["LLB"].get_force()
- f_llf = self.simulation.pressure_sensors[self.robot_index]["LLF"].get_force()
- f_lrf = self.simulation.pressure_sensors[self.robot_index]["LRF"].get_force()
- f_lrb = self.simulation.pressure_sensors[self.robot_index]["LRB"].get_force()
-
- f_rlb = self.simulation.pressure_sensors[self.robot_index]["RLB"].get_force()
- f_rlf = self.simulation.pressure_sensors[self.robot_index]["RLF"].get_force()
- f_rrf = self.simulation.pressure_sensors[self.robot_index]["RRF"].get_force()
- f_rrb = self.simulation.pressure_sensors[self.robot_index]["RRB"].get_force()
-
- self.foot_msg_left.left_back = f_llb[0]
- self.foot_msg_left.left_front = f_llf[0]
- self.foot_msg_left.right_front = f_lrf[0]
- self.foot_msg_left.right_back = f_lrb[0]
- self.left_foot_pressure_publisher.publish(self.foot_msg_left)
-
- self.foot_msg_right.left_back = f_rlb[0]
- self.foot_msg_right.left_front = f_rlf[0]
- self.foot_msg_right.right_front = f_rrf[0]
- self.foot_msg_right.right_back = f_rrb[0]
- self.right_foot_pressure_publisher.publish(self.foot_msg_right)
-
- self.foot_msg_left.left_back = f_llb[1]
- self.foot_msg_left.left_front = f_llf[1]
- self.foot_msg_left.right_front = f_lrf[1]
- self.foot_msg_left.right_back = f_lrb[1]
- self.left_foot_pressure_publisher_filtered.publish(self.foot_msg_left)
-
- self.foot_msg_right.left_back = f_rlb[1]
- self.foot_msg_right.left_front = f_rlf[1]
- self.foot_msg_right.right_front = f_rrf[1]
- self.foot_msg_right.right_back = f_rrb[1]
- self.right_foot_pressure_publisher_filtered.publish(self.foot_msg_right)
-
- # center position on foot
- pos_x = 0.085
- pos_y = 0.045
- threshold = 0.0
-
- cop_l = PointStamped()
- cop_l.header.frame_id = "l_sole"
- cop_l.header.stamp = rospy.Time.from_seconds(self.simulation.time)
- sum_of_forces = f_llb[1] + f_llf[1] + f_lrf[1] + f_lrb[1]
- if sum_of_forces > threshold:
- cop_l.point.x = (f_llf[1] + f_lrf[1] - f_llb[1] - f_lrb[1]) * pos_x / sum_of_forces
- cop_l.point.x = max(min(cop_l.point.x, pos_x), -pos_x)
- cop_l.point.y = (f_llf[1] + f_llb[1] - f_lrf[1] - f_lrb[1]) * pos_y / sum_of_forces
- cop_l.point.y = max(min(cop_l.point.y, pos_y), -pos_y)
- else:
- cop_l.point.x = 0
- cop_l.point.y = 0
- self.cop_l_pub_.publish(cop_l)
-
- cop_r = PointStamped()
- cop_r.header.frame_id = "r_sole"
- cop_r.header.stamp = rospy.Time.from_seconds(self.simulation.time)
- sum_of_forces = f_rlb[1] + f_rlf[1] + f_rrf[1] + f_rrb[1]
- if sum_of_forces > threshold:
- cop_r.point.x = (f_rlf[1] + f_rrf[1] - f_rlb[1] - f_rrb[1]) * pos_x / sum_of_forces
- cop_r.point.x = max(min(cop_r.point.x, pos_x), -pos_x)
- cop_r.point.y = (f_rlf[1] + f_rlb[1] - f_rrf[1] - f_rrb[1]) * pos_y / sum_of_forces
- cop_r.point.y = max(min(cop_r.point.y, pos_y), -pos_y)
- else:
- cop_r.point.x = 0
- cop_r.point.y = 0
- self.cop_r_pub_.publish(cop_r)
-
- def publish_true_odom(self):
- position, orientation = self.simulation.get_robot_pose()
- self.odom_msg.pose.pose.position.x = position[0]
- self.odom_msg.pose.pose.position.y = position[1]
- self.odom_msg.pose.pose.position.z = position[2]
- self.odom_msg.pose.pose.orientation.x = orientation[0]
- self.odom_msg.pose.pose.orientation.y = orientation[1]
- self.odom_msg.pose.pose.orientation.z = orientation[2]
- self.odom_msg.pose.pose.orientation.w = orientation[3]
- self.true_odom_publisher.publish(self.odom_msg)
-
- def joint_goal_cb(self, msg: JointCommand):
- # only put new goals into the goal vector
- i = 0
- for name in msg.joint_names:
- self.simulation.joints[self.robot_index][name].set_position(msg.positions[i])
- i += 1
-
- def reset_cb(self, msg):
- self.simulation.reset()
-
- def _dynamic_reconfigure_callback(self, config, level):
- self.simulation.set_foot_dynamics(
- config["contact_damping"],
- config["contact_stiffness"],
- config["joint_damping"],
- config["lateral_friction"],
- config["spinning_friction"],
- config["rolling_friction"],
- )
- self.simulation.set_filter_params(config["cutoff"], config["order"])
- return config
diff --git a/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt b/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt
index 405b00503..cb326d372 100644
--- a/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt
+++ b/bitbots_simulation/bitbots_webots_sim/CMakeLists.txt
@@ -1,76 +1,11 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_webots_sim)
-# Add support for C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
-
-find_package(bitbots_msgs REQUIRED)
-find_package(rosgraph_msgs REQUIRED)
-find_package(std_msgs REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(bitbots_docs REQUIRED)
-find_package(urdf REQUIRED)
-find_package(nav_msgs REQUIRED)
-find_package(rclpy REQUIRED)
-find_package(sensor_msgs REQUIRED)
-find_package(gazebo_msgs REQUIRED)
-
-set(INCLUDE_DIRS
- ${bitbots_msgs_INCLUDE_DIRS}
- ${rosgraph_msgs_INCLUDE_DIRS}
- ${std_msgs_INCLUDE_DIRS}
- ${ament_cmake_INCLUDE_DIRS}
- ${bitbots_docs_INCLUDE_DIRS}
- ${urdf_INCLUDE_DIRS}
- ${nav_msgs_INCLUDE_DIRS}
- ${rclpy_INCLUDE_DIRS}
- ${sensor_msgs_INCLUDE_DIRS}
- ${gazebo_msgs_INCLUDE_DIRS})
-include_directories(${INCLUDE_DIRS})
-
-set(LIBRARY_DIRS
- ${bitbots_msgs_LIBRARY_DIRS}
- ${rosgraph_msgs_LIBRARY_DIRS}
- ${std_msgs_LIBRARY_DIRS}
- ${ament_cmake_LIBRARY_DIRS}
- ${bitbots_docs_LIBRARY_DIRS}
- ${urdf_LIBRARY_DIRS}
- ${nav_msgs_LIBRARY_DIRS}
- ${rclpy_LIBRARY_DIRS}
- ${sensor_msgs_LIBRARY_DIRS}
- ${gazebo_msgs_LIBRARY_DIRS})
-link_directories(${LIBRARY_DIRS})
-
-set(LIBS
- ${bitbots_msgs_LIBRARIES}
- ${rosgraph_msgs_LIBRARIES}
- ${std_msgs_LIBRARIES}
- ${ament_cmake_LIBRARIES}
- ${bitbots_docs_LIBRARIES}
- ${urdf_LIBRARIES}
- ${nav_msgs_LIBRARIES}
- ${rclpy_LIBRARIES}
- ${sensor_msgs_LIBRARIES}
- ${gazebo_msgs_LIBRARIES})
-
-include(${CMAKE_BINARY_DIR}/../bitbots_docs/enable_bitbots_docs.cmake)
enable_bitbots_docs()
-ament_export_dependencies(bitbots_msgs)
-ament_export_dependencies(rosgraph_msgs)
-ament_export_dependencies(std_msgs)
-ament_export_dependencies(ament_cmake)
-ament_export_dependencies(bitbots_docs)
-ament_export_dependencies(urdf)
-ament_export_dependencies(nav_msgs)
-ament_export_dependencies(rclpy)
-ament_export_dependencies(sensor_msgs)
-ament_export_dependencies(gazebo_msgs)
-ament_export_include_directories(${INCLUDE_DIRS})
-
install(DIRECTORY protos DESTINATION share/${PROJECT_NAME})
install(DIRECTORY worlds DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_team_communication/bitbots_team_communication/CMakeLists.txt b/bitbots_team_communication/bitbots_team_communication/CMakeLists.txt
index 35bd6de10..93f0dece8 100644
--- a/bitbots_team_communication/bitbots_team_communication/CMakeLists.txt
+++ b/bitbots_team_communication/bitbots_team_communication/CMakeLists.txt
@@ -3,16 +3,7 @@ project(bitbots_team_communication)
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_python REQUIRED)
-find_package(rclpy REQUIRED)
-find_package(std_msgs REQUIRED)
-find_package(bitbots_msgs REQUIRED)
-find_package(geometry_msgs REQUIRED)
-find_package(tf2 REQUIRED)
-find_package(tf2_ros REQUIRED)
-find_package(tf2_geometry_msgs REQUIRED)
-find_package(bitbots_utils REQUIRED)
find_package(bitbots_docs REQUIRED)
-
find_package(Protobuf REQUIRED)
protobuf_generate_python(