Skip to content

Commit

Permalink
Merge branch 'main' into feature/jazzy-ubuntu2404-devcontainer
Browse files Browse the repository at this point in the history
  • Loading branch information
Flova committed Jan 20, 2025
2 parents 799349f + a851e49 commit be9c81d
Show file tree
Hide file tree
Showing 40 changed files with 593 additions and 891 deletions.
73 changes: 2 additions & 71 deletions bitbots_behavior/bitbots_blackboard/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@
from bitbots_msgs.msg import Audio, HeadMode, RobotControlState

THeadMode: TypeAlias = Literal[ # type: ignore[valid-type]
HeadMode.BALL_MODE,
HeadMode.FIELD_FEATURES,
HeadMode.SEARCH_BALL,
HeadMode.SEARCH_FIELD_FEATURES,
HeadMode.LOOK_FORWARD,
HeadMode.DONT_MOVE,
HeadMode.BALL_MODE_PENALTY,
HeadMode.LOOK_FRONT,
HeadMode.SEARCH_BALL_PENALTY,
HeadMode.SEARCH_FRONT,
]


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,15 +45,15 @@ class SearchBall(AbstractHeadModeElement):
"""Look for ball"""

def perform(self):
self.blackboard.misc.set_head_duty(HeadMode.BALL_MODE)
self.blackboard.misc.set_head_duty(HeadMode.SEARCH_BALL)
return self.pop()


class LookAtFieldFeatures(AbstractHeadModeElement):
"""Look generally for all features on the field (ball, goals, corners, center point)"""

def perform(self):
self.blackboard.misc.set_head_duty(HeadMode.FIELD_FEATURES)
self.blackboard.misc.set_head_duty(HeadMode.SEARCH_FIELD_FEATURES)
return self.pop()


Expand All @@ -77,13 +77,13 @@ class LookAtBallPenalty(AbstractHeadModeElement):
"""Ball Mode adapted for Penalty Kick"""

def perform(self):
self.blackboard.misc.set_head_duty(HeadMode.BALL_MODE_PENALTY)
self.blackboard.misc.set_head_duty(HeadMode.SEARCH_BALL_PENALTY)
return self.pop()


class LookAtFront(AbstractHeadModeElement):
"""Search in front of the robot"""

def perform(self):
self.blackboard.misc.set_head_duty(HeadMode.LOOK_FRONT)
self.blackboard.misc.set_head_duty(HeadMode.SEARCH_FRONT)
return self.pop()
5 changes: 5 additions & 0 deletions bitbots_lowlevel/bitbots_buttons/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
5 changes: 5 additions & 0 deletions bitbots_lowlevel/bitbots_ros_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
5 changes: 5 additions & 0 deletions bitbots_misc/bitbots_basler_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
1 change: 1 addition & 0 deletions bitbots_misc/bitbots_basler_camera/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@

<author email="[email protected]">Hamburg Bit-Bots</author>

<depend>backward_ros</depend>
<depend>bitbots_docs</depend>
<depend>camera_info_manager</depend>
<depend>cv_bridge</depend>
Expand Down
17 changes: 11 additions & 6 deletions bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
8 changes: 4 additions & 4 deletions bitbots_misc/bitbots_extrinsic_calibration/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,17 +9,17 @@
<maintainer email="[email protected]">Hamburg Bit-Bots</maintainer>

<license>MIT</license>

<author email="[email protected]">Florian Vahl</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
<depend>bitbots_docs</depend>
<depend>rot_conv</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>rot_conv</depend>
<depend>backward_ros</depend>
<depend>tf2</depend>

<export>
<bitbots_documentation>
Expand Down
6 changes: 0 additions & 6 deletions bitbots_misc/bitbots_robot_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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})
Expand Down
16 changes: 8 additions & 8 deletions bitbots_misc/bitbots_teleop/scripts/teleop_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -222,12 +222,12 @@ def loop(self):
self.head_pub.publish(self.head_msg)
elif key == "0":
# Search for Ball and track it if found
self.head_mode_msg.head_mode = HeadMode.BALL_MODE
assert int(key) == HeadMode.BALL_MODE
self.head_mode_msg.head_mode = HeadMode.SEARCH_BALL
assert int(key) == HeadMode.SEARCH_BALL
elif key == "1":
# Look generally for all features on the field (ball, goals, corners, center point)
self.head_mode_msg.head_mode = HeadMode.FIELD_FEATURES
assert int(key) == HeadMode.FIELD_FEATURES
self.head_mode_msg.head_mode = HeadMode.SEARCH_FIELD_FEATURES
assert int(key) == HeadMode.SEARCH_FIELD_FEATURES
elif key == "2":
# Simply look directly forward
self.head_mode_msg.head_mode = HeadMode.LOOK_FORWARD
Expand All @@ -238,12 +238,12 @@ def loop(self):
assert int(key) == HeadMode.DONT_MOVE
elif key == "4":
# Ball Mode adapted for Penalty Kick
self.head_mode_msg.head_mode = HeadMode.BALL_MODE_PENALTY
assert int(key) == HeadMode.BALL_MODE_PENALTY
self.head_mode_msg.head_mode = HeadMode.SEARCH_BALL_PENALTY
assert int(key) == HeadMode.SEARCH_BALL_PENALTY
elif key == "5":
# Do a pattern which only looks in front of the robot
self.head_mode_msg.head_mode = HeadMode.LOOK_FRONT
assert int(key) == HeadMode.LOOK_FRONT
self.head_mode_msg.head_mode = HeadMode.SEARCH_FRONT
assert int(key) == HeadMode.SEARCH_FRONT
elif key == "y":
# kick left forward
pass
Expand Down
8 changes: 7 additions & 1 deletion bitbots_misc/bitbots_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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})
Expand Down
3 changes: 2 additions & 1 deletion bitbots_misc/bitbots_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,12 @@
<maintainer email="[email protected]">Hamburg Bit-Bots</maintainer>

<license>MIT</license>

<author email="[email protected]">Hamburg Bit-Bots</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
<depend>bitbots_docs</depend>
<depend>python3-yaml</depend>
<depend>python3-transforms3d</depend>
Expand Down
9 changes: 7 additions & 2 deletions bitbots_motion/bitbots_dynamic_kick/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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_toolbox REQUIRED)
Expand All @@ -24,7 +30,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(Python3 COMPONENTS Interpreter Development)

Expand Down
5 changes: 5 additions & 0 deletions bitbots_motion/bitbots_dynup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,11 @@ if(ipo_supported)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -flto=4")
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)

Expand Down
7 changes: 6 additions & 1 deletion bitbots_motion/bitbots_hcm/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
cmake_minimum_required(VERSION 3.12)
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)
Expand All @@ -18,7 +23,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})
Expand Down
8 changes: 5 additions & 3 deletions bitbots_motion/bitbots_head_mover/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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()
Expand All @@ -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)
Expand All @@ -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)

generate_parameter_library(
head_parameters # cmake target name for the parameter library
config/head_config.yml)
Expand Down
Loading

0 comments on commit be9c81d

Please sign in to comment.